From b35b1e19c41eef0cefce89d0e3215d22cfd682be Mon Sep 17 00:00:00 2001 From: Christian Ehlers Date: Tue, 26 Jan 2021 15:07:29 +0100 Subject: [PATCH 01/39] Update sqnsupgrade.py Flush read buffer before starting stp session --- lib/sqnsupgrade/sqnsupgrade.py | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/lib/sqnsupgrade/sqnsupgrade.py b/lib/sqnsupgrade/sqnsupgrade.py index 23cc41c..7c8db01 100644 --- a/lib/sqnsupgrade/sqnsupgrade.py +++ b/lib/sqnsupgrade/sqnsupgrade.py @@ -1,7 +1,7 @@ #!/usr/bin/env python -VERSION = "1.2.6" +VERSION = "1.2.7" -# Copyright (c) 2019, Pycom Limited. +# Copyright (c) 2021, Pycom Limited. # # This software is licensed under the GNU GPL version 3 or any # later version, with permitted additional terms. For more information @@ -350,7 +350,7 @@ def __run(self, file_path=None, baudrate=921600, port=None, resume=False, load_f load_fff = True if force_fff else load_fff target_baudrate = baudrate baudrate = self.__modem_speed if self.__speed_detected else baudrate - if debug: print('mirror? {} recover? {} resume? {} direct? {} atneg_only? {} bootrom? {} load_fff? {}'.format(mirror, recover, resume, direct, atneg_only, bootrom, load_fff)) + if debug: print('file_path? {} mirror? {} recover? {} resume? {} direct? {} atneg_only? {} bootrom? {} load_fff? {}'.format(file_path, mirror, recover, resume, direct, atneg_only, bootrom, load_fff)) if debug: print('baudrate: {} target_baudrate: {}'.format(baudrate, target_baudrate)) abort = True external = False @@ -522,7 +522,7 @@ def __run(self, file_path=None, baudrate=921600, port=None, resume=False, load_f return self.uart_mirror(rgbled) elif bootrom: - if verbose: print('Starting STP') + if verbose: print('Starting STP [BR]') else: if verbose: if load_fff: @@ -547,7 +547,6 @@ def __run(self, file_path=None, baudrate=921600, port=None, resume=False, load_f except Exception as ex: if debug: print('Exception: {}'.format(ex)) pass - self.__serial.read() elif recover and (not direct): if atneg: @@ -576,7 +575,7 @@ def __run(self, file_path=None, baudrate=921600, port=None, resume=False, load_f else: if debug: print('Starting STP mode...') self.__serial.write(b"AT+STP\n") - response = self.read_rsp(size=2) + response = self.read_rsp(size=4) if not b'OK' in response: print('Failed to start STP mode!') reconnect_uart() @@ -584,7 +583,10 @@ def __run(self, file_path=None, baudrate=921600, port=None, resume=False, load_f try: if debug: - if verbose: print('Starting STP code upload') + if verbose: print('Starting STP code upload with pkgdebug={}'.format(pkgdebug)) + time.sleep(.1) + self.__serial.read() + time.sleep(.1) start = stp.start(blob, blobsize, self.__serial, baudrate, AT=False, debug=debug, pkgdebug=pkgdebug) if debug: print('start returned {} type {}'.format(start, type(start))) if start == True: From a28c43ea23f44e46aebba03958c97e91e96f0e44 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Mon, 14 Dec 2020 18:59:34 +0100 Subject: [PATCH 02/39] rename --- pysense-2/{main.py => sensors.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename pysense-2/{main.py => sensors.py} (100%) diff --git a/pysense-2/main.py b/pysense-2/sensors.py similarity index 100% rename from pysense-2/main.py rename to pysense-2/sensors.py From c993a7f5ec75cb1c4ed809b0b18f1893b6b83a29 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Mon, 14 Dec 2020 19:00:18 +0100 Subject: [PATCH 03/39] support wake from accelerometer (v16) lots of changes inside: - use LAT instead of PORT from writing - refactor write_byte(), read_byte(), write_bit(), read_bit() - check usb product ID in init() - remove "wake_int" which is only for Pysense1 (RA5) - refactor "wake_int_pin", which is for RC1 - add attempt to wake PIC from RC1 if it is not available in init() - rewrite go_to_sleep() and add support for new CMD_GO_NAP command - require FW v16 in init() --- pysense-2/lib/pycoproc.py | 211 +++++++++++++++++++++++--------------- pysense-2/main.py | 121 ++++++++++++++++++++++ 2 files changed, 249 insertions(+), 83 deletions(-) create mode 100644 pysense-2/main.py diff --git a/pysense-2/lib/pycoproc.py b/pysense-2/lib/pycoproc.py index 7ddef19..3a607ac 100644 --- a/pysense-2/lib/pycoproc.py +++ b/pysense-2/lib/pycoproc.py @@ -32,14 +32,21 @@ class Pycoproc: CMD_POKE = const(0x01) CMD_MAGIC = const(0x02) CMD_HW_VER = const(0x10) - CMD_FW_VER = const(0x11) - CMD_PROD_ID = const(0x12) + CMD_FW_VER = const(0x11) #define SW_VERSION (15) + CMD_PROD_ID = const(0x12) #USB product ID, e.g. PYSENSE (0xF012) CMD_SETUP_SLEEP = const(0x20) CMD_GO_SLEEP = const(0x21) CMD_CALIBRATE = const(0x22) + CMD_GO_NAP = const(0x23) CMD_BAUD_CHANGE = const(0x30) CMD_DFU = const(0x31) CMD_RESET = const(0x40) + # CMD_GO_NAP options + SD_CARD_OFF = const(0x1) + SENSORS_OFF = const(0x2) + ACCELEROMETER_OFF = const(0x4) + FIPY_OFF = const(0x8) + REG_CMD = const(0) REG_ADDRL = const(1) @@ -62,17 +69,26 @@ class Pycoproc: OPTION_REG_ADDR = const(0x95) _ADCON0_CHS_POSN = const(0x02) + _ADCON0_CHS_AN5 = const(0x5) # AN5 / RC1 + _ADCON0_CHS_AN6 = const(0x6) # AN6 / RC2 _ADCON0_ADON_MASK = const(0x01) - _ADCON1_ADCS_POSN = const(0x04) + _ADCON0_ADCS_F_OSC_64 = const(0x6) # A/D Conversion Clock _ADCON0_GO_nDONE_MASK = const(0x02) + _ADCON1_ADCS_POSN = const(0x04) ADRESL_ADDR = const(0x09B) ADRESH_ADDR = const(0x09C) TRISA_ADDR = const(0x08C) + TRISB_ADDR = const(0x08D) TRISC_ADDR = const(0x08E) + LATA_ADDR = const(0x10C) + LATB_ADDR = const(0x10D) + LATC_ADDR = const(0x10E) + PORTA_ADDR = const(0x00C) + PORTB_ADDR = const(0x00C) PORTC_ADDR = const(0x00E) WPUA_ADDR = const(0x20C) @@ -85,6 +101,16 @@ class Pycoproc: EXP_RTC_PERIOD = const(7000) + @staticmethod + def wake_up(): + # P9 is connected to RC1, make P9 an output + p9 = Pin("P9", mode=Pin.OUT) + # toggle rc1 to trigger wake up + p9(1) + time.sleep(0.1) + p9(0) + time.sleep(0.1) + def __init__(self, i2c=None, sda='P22', scl='P21'): if i2c is not None: self.i2c = i2c @@ -95,37 +121,52 @@ def __init__(self, i2c=None, sda='P22', scl='P21'): self.scl = scl self.clk_cal_factor = 1 self.reg = bytearray(6) - self.wake_int = False - self.wake_int_pin = False - self.wake_int_pin_rising_edge = True # Make sure we are inserted into the # correct board and can talk to the PIC - try: - self.read_fw_version() - except Exception as e: - raise Exception('Board not detected: {}'.format(e)) + retry = 0 + while True: + try: + self.read_fw_version() + break + except Exception as e: + if retry > 10: + raise Exception('Board not detected: {}'.format(e)) + print("Couldn't init Pycoproc. Maybe the PIC is still napping. Try to wake it. ({}, {})".format(retry, e)) + Pycoproc.wake_up() + # # p9 is connected to RC1, toggle it to wake PIC + # p9 = Pin("P9", mode=Pin.OUT) + # p9(1) + # time.sleep(0.1) + # p9(0) + # time.sleep(0.1) + # Pin("P9", mode=Pin.IN) + retry += 1 # init the ADC for the battery measurements - self.poke_memory(ANSELC_ADDR, 1 << 2) - self.poke_memory(ADCON0_ADDR, (0x06 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) - self.poke_memory(ADCON1_ADDR, (0x06 << _ADCON1_ADCS_POSN)) - # enable the pull-up on RA3 - self.poke_memory(WPUA_ADDR, (1 << 3)) + self.write_byte(ANSELC_ADDR, 1 << 2) # RC2 analog input + self.write_byte(ADCON0_ADDR, (_ADCON0_CHS_AN6 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) # select analog channel and enable ADC + self.write_byte(ADCON1_ADDR, (_ADCON0_ADCS_F_OSC_64 << _ADCON1_ADCS_POSN)) # ADC conversion clock - # set RC6 and RC7 as outputs and enable power to the sensors and the GPS - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 6)) - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) + # enable the pull-up on RA3 + self.write_byte(WPUA_ADDR, (1 << 3)) + # set RC6 and RC7 as outputs + self.write_bit(TRISC_ADDR, 6, 0) # 3V3SENSOR_A, power to Accelerometer + self.write_bit(TRISC_ADDR, 7, 0) # PWR_CTRL power to other sensors - self.gps_standby(False) - self.sensor_power() - self.sd_power() + # enable power to the sensors and the GPS + self.gps_standby(False) # GPS, RC4 + self.sensor_power() # PWR_CTRL, RC7 + self.sd_power() # LP_CTRL, RA5 + usb_pid=self.read_product_id() + if usb_pid != 0xf012: + raise ValueError('Not a Pysense2/Pytrack2 ({})'.format(usb_pid)) # for Pysense/Pytrack 2.0, the minimum firmware version is 15 - if self.read_fw_version() < 15: - raise ValueError('Firmware out of date') - + fw = self.read_fw_version() + if fw < 15: + raise ValueError('Firmware out of date', fw) def _write(self, data, wait=True): self.i2c.writeto(I2C_SLAVE_ADDR, data) @@ -162,11 +203,11 @@ def read_product_id(self): d = self._read(2) return (d[1] << 8) + d[0] - def peek_memory(self, addr): + def read_byte(self, addr): self._write(bytes([CMD_PEEK, addr & 0xFF, (addr >> 8) & 0xFF])) return self._read(1)[0] - def poke_memory(self, addr, value): + def write_byte(self, addr, value): self._write(bytes([CMD_POKE, addr & 0xFF, (addr >> 8) & 0xFF, value & 0xFF])) def magic_write_read(self, addr, _and=0xFF, _or=0, _xor=0): @@ -182,6 +223,25 @@ def mask_bits_in_memory(self, addr, mask): def set_bits_in_memory(self, addr, bits): self.magic_write_read(addr, _or=bits) + def read_bit(self, address, bit): + b = self.read_byte(address) + # print("{0:08b}".format(b)) + mask = (1<> 8) & 0xFF, (time_s >> 16) & 0xFF])) - def go_to_sleep(self, gps=True): + def go_to_sleep(self, gps=True, pycom_module_off=True, accelerometer_off=True, wake_interrupt=False): # enable or disable back-up power to the GPS receiver self.gps_standby(gps) - self.sensor_power(False) - self.sd_power(False) # disable the ADC - self.poke_memory(ADCON0_ADDR, 0) + self.write_byte(ADCON0_ADDR, 0) - if self.wake_int: - # Don't touch RA3, RA5 or RC1 so that interrupt wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~((1 << 6) | (1 << 7) | (1 << 1))) - else: - # disable power to the accelerometer, and don't touch RA3 so that button wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~(0)) - - self.poke_memory(ANSELB_ADDR, 0xFF) - - # check if INT pin (PIC RC1), should be used for wakeup - if self.wake_int_pin: - if self.wake_int_pin_rising_edge: - self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin - else: - self.mask_bits_in_memory(OPTION_REG_ADDR, ~(1 << 6)) # falling edge of INT pin + # RC0, RC1, RC2, analog input + self.set_bits_in_memory(TRISC_ADDR, (1<<2) | (1<<1) | (1<<0) ) + self.set_bits_in_memory(ANSELC_ADDR, (1<<2) | (1<<1) | (1<<0) ) + + # RA4 analog input + self.set_bits_in_memory(TRISA_ADDR, (1<<4) ) + self.set_bits_in_memory(ANSELA_ADDR, (1<<4) ) + + # RB4, RB5 analog input + self.set_bits_in_memory(TRISB_ADDR, (1<<5) | (1<<4) ) + self.set_bits_in_memory(ANSELB_ADDR, (1<<5) | (1<<4) ) + + # actually only B4 and B5 + # todo: tris=1? + self.write_byte(ANSELB_ADDR, 0xff) + + if wake_interrupt: + # print("enable wake up PIC from RC1") + self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin self.mask_bits_in_memory(ANSELC_ADDR, ~(1 << 1)) # disable analog function for RC1 pin self.set_bits_in_memory(TRISC_ADDR, 1 << 1) # make RC1 input pin self.mask_bits_in_memory(INTCON_ADDR, ~(1 << 1)) # clear INTF self.set_bits_in_memory(INTCON_ADDR, 1 << 4) # enable interrupt; set INTE) - self._write(bytes([CMD_GO_SLEEP]), wait=False) + nap_options = SD_CARD_OFF | SENSORS_OFF + if pycom_module_off: + nap_options |= FIPY_OFF + if accelerometer_off: + nap_options |= ACCELEROMETER_OFF + + # print("CMD_GO_NAP {0:08b}".format(nap_options)) + self._write(bytes([CMD_GO_NAP, nap_options]), wait=False) def calibrate_rtc(self): # the 1.024 factor is because the PIC LF operates at 31 KHz @@ -248,72 +315,50 @@ def calibrate_rtc(self): self.clk_cal_factor = (EXP_RTC_PERIOD / period) * (1000 / 1024) if self.clk_cal_factor > 1.25 or self.clk_cal_factor < 0.75: self.clk_cal_factor = 1 + time.sleep(0.5) def button_pressed(self): - button = self.peek_memory(PORTA_ADDR) & (1 << 3) + button = self.read_bit(PORTA_ADDR, 3) return not button def read_battery_voltage(self): self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) time.sleep_us(50) - while self.peek_memory(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: + while self.read_byte(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: time.sleep_us(100) - adc_val = (self.peek_memory(ADRESH_ADDR) << 2) + (self.peek_memory(ADRESL_ADDR) >> 6) + adc_val = (self.read_byte(ADRESH_ADDR) << 2) + (self.read_byte(ADRESL_ADDR) >> 6) return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET - def setup_int_wake_up(self, rising, falling): - """ rising is for activity detection, falling for inactivity """ - wake_int = False - if rising: - self.set_bits_in_memory(IOCAP_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAP_ADDR, ~(1 << 5)) - - if falling: - self.set_bits_in_memory(IOCAN_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAN_ADDR, ~(1 << 5)) - self.wake_int = wake_int - - def setup_int_pin_wake_up(self, rising_edge = True): - """ allows wakeup to be made by the INT pin (PIC -RC1) """ - self.wake_int_pin = True - self.wake_int_pin_rising_edge = rising_edge - def gps_standby(self, enabled=True): # make RC4 an output - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 4)) + self.write_bit(TRISC_ADDR, 4, 0) if enabled: # drive RC4 low - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 4)) + self.write_bit(LATC_ADDR, 4, 0) else: # drive RC4 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 4) + self.write_bit(LATC_ADDR, 4, 1) def sensor_power(self, enabled=True): # make RC7 an output - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) + self.write_bit(TRISC_ADDR, 7, 0) if enabled: # drive RC7 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) + self.write_bit(LATC_ADDR, 7, 1) else: # drive RC7 low - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) + self.write_bit(LATC_ADDR, 7, 0) def sd_power(self, enabled=True): # make RA5 an output - self.mask_bits_in_memory(TRISA_ADDR, ~(1 << 5)) + self.write_bit(TRISA_ADDR, 5, 0) if enabled: # drive RA5 high - self.set_bits_in_memory(PORTA_ADDR, 1 << 5) + self.write_bit(LATA_ADDR, 5, 1) else: # drive RA5 low - self.mask_bits_in_memory(PORTA_ADDR, ~(1 << 5)) - + self.write_bit(LATA_ADDR, 5, 0) - # at the end: def reset_cmd(self): self._send_cmd(CMD_RESET) return diff --git a/pysense-2/main.py b/pysense-2/main.py new file mode 100644 index 0000000..3b2dbda --- /dev/null +++ b/pysense-2/main.py @@ -0,0 +1,121 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020, Pycom Limited. +# +# This software is licensed under the GNU GPL version 3 or any +# later version, with permitted additional terms. For more information +# see the Pycom Licence v1.0 document supplied with this file, or +# available at https://www.pycom.io/opensource/licensing +# + +# See https://docs.pycom.io for more information regarding library specifics + +import time +import pycom +import struct +from machine import Pin +from pysense import Pysense +import machine + +from LIS2HH12 import LIS2HH12 +from SI7006A20 import SI7006A20 +from LTR329ALS01 import LTR329ALS01 +from MPL3115A2 import MPL3115A2,ALTITUDE,PRESSURE + +# This script demonstrates two examples: +# * go to ultra low power mode (~10uA @3.75V) with all sensors, incl accelerometer and also pycom module (Fipy, Gpy, etc) off +# * go to low power mode (~165uA @3.75V) with accelerometer on, pycom module in deepsleep and wake from accelerometer interrupt +wake_from_accelerometer = True +sleep_time_s = 300 + +def accelerometer(): + print("ACCELEROMETER:", "accel:", accelerometer_sensor.acceleration(), "roll:", accelerometer_sensor.roll(), "pitch:", accelerometer_sensor.pitch(), "x/y/z:", accelerometer_sensor.x, accelerometer_sensor.y, accelerometer_sensor.z ) + +def activity_int_handler(pin_o): + if pin_o(): + print('[Activity]') + # blue + pycom.rgbled(0x00000A) + else: + print('[Inactivity]') + # yellow + pycom.rgbled(0x0A0A00) + +def activity_int_handler_none(pin_o): + pass + +def blink(ct=5, color=0x220022, on_ms=100, off_ms=100 ): + while ct >= 0 : + ct -= 1 + pycom.rgbled(color) + time.sleep_ms(on_ms) + pycom.rgbled(0x000000) + time.sleep_ms(off_ms) + +def wait(color=0x0a0a0a): + print("wait for button ...") + blink(5, color) + pycom.rgbled(color) + ct = 0 + while True: + if pycoproc.button_pressed(): + blink(5, color) + print("button pressed") + break + time.sleep(0.1) + ct += 1 + if ct % 10 == 0: + print('.', end='') + pycom.rgbled(color) + +############################################################### +pycom.heartbeat(False) +pycom.rgbled(0x0a0500) + +try: + print("lte deinit") + from network import LTE + lte = LTE() + lte.deinit() +except: + pass + +pycom.rgbled(0x0a0a0a) +print("pycoproc init") +pycoproc = Pysense() + +b = pycoproc.read_battery_voltage() +print("battery {:.2f} V".format(b)) + +pycoproc.setup_sleep(sleep_time_s) + +wait(0x000a00) # blink green, wait for user to press MCLR button, blink green + +accelerometer_sensor = LIS2HH12() +accelerometer() + +if wake_from_accelerometer == True: + # configure accelerometer interrupt sensitivity + + # accelerometer_sensor.enable_activity_interrupt(8000, 200, activity_int_handler) # low sensitivty + # 2000mG (2G), 200ms + # accelerometer_sensor.enable_activity_interrupt(2000, 200, activity_int_handler) # medium sensitivity + accelerometer_sensor.enable_activity_interrupt( 100, 200, activity_int_handler) # high sensitivity + # accelerometer_sensor.enable_activity_interrupt(63, 160, activity_int_handler) # ultra sensitivty + + wait(0x0A000A) # blink purple, wait for user to press MCLR button, blink purple + + print("enable pycom module to wake up from accelerometer interrupt") + wake_pins = [Pin('P13', mode=Pin.IN, pull=Pin.PULL_DOWN)] + machine.pin_sleep_wakeup(wake_pins, machine.WAKEUP_ANY_HIGH, True) + + print("put pycoproc to sleep") + pycoproc.go_to_sleep(pycom_module_off=False, accelerometer_off=False, wake_interrupt=True) + + print("put pycom module to deepsleep", sleep_time_s, "s") + machine.deepsleep(sleep_time_s * 1000) +else: + print("put pycoproc to sleep, turn off everything") + pycoproc.go_to_sleep() + +print("we never reach here!") From cbb71df9ca0e24a80040906527ff0136ff6eddf8 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Fri, 29 Jan 2021 17:09:26 +0100 Subject: [PATCH 04/39] pytrack and some refactoring - move setup_sleep further down, because it makes us lose REPL - remove pysense wrapper class and use pycoproc instead - update pycoproc to support pytrack as well - some refactoring/cleanup/comments/logging in main.py - mv sensors.py to pysense.py --- pysense-2/lib/pycoproc.py | 24 +++-- pysense-2/lib/pysense.py | 20 ---- pysense-2/main.py | 153 +++++++++++++++++---------- pysense-2/{sensors.py => pysense.py} | 6 +- 4 files changed, 111 insertions(+), 92 deletions(-) delete mode 100644 pysense-2/lib/pysense.py rename pysense-2/{sensors.py => pysense.py} (96%) diff --git a/pysense-2/lib/pycoproc.py b/pysense-2/lib/pycoproc.py index 3a607ac..d2480df 100644 --- a/pysense-2/lib/pycoproc.py +++ b/pysense-2/lib/pycoproc.py @@ -101,6 +101,9 @@ class Pycoproc: EXP_RTC_PERIOD = const(7000) + USB_PID_PYSENSE = const(0xf012) + USB_PID_PYTRACK = const(0xf013) + @staticmethod def wake_up(): # P9 is connected to RC1, make P9 an output @@ -143,6 +146,14 @@ def __init__(self, i2c=None, sda='P22', scl='P21'): # Pin("P9", mode=Pin.IN) retry += 1 + usb_pid=self.read_product_id() + if usb_pid != USB_PID_PYSENSE and usb_pid != USB_PID_PYTRACK: + raise ValueError('Not a Pysense2/Pytrack2 ({})'.format(hex(usb_pid))) + # for Pysense/Pytrack 2.0, the minimum firmware version is 15 + fw = self.read_fw_version() + if fw < 16: + raise ValueError('Firmware out of date', fw) + # init the ADC for the battery measurements self.write_byte(ANSELC_ADDR, 1 << 2) # RC2 analog input self.write_byte(ADCON0_ADDR, (_ADCON0_CHS_AN6 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) # select analog channel and enable ADC @@ -160,13 +171,6 @@ def __init__(self, i2c=None, sda='P22', scl='P21'): self.sensor_power() # PWR_CTRL, RC7 self.sd_power() # LP_CTRL, RA5 - usb_pid=self.read_product_id() - if usb_pid != 0xf012: - raise ValueError('Not a Pysense2/Pytrack2 ({})'.format(usb_pid)) - # for Pysense/Pytrack 2.0, the minimum firmware version is 15 - fw = self.read_fw_version() - if fw < 15: - raise ValueError('Firmware out of date', fw) def _write(self, data, wait=True): self.i2c.writeto(I2C_SLAVE_ADDR, data) @@ -244,6 +248,8 @@ def write_bit(self, address, bit, level): def setup_sleep(self, time_s): try: + time.sleep_ms(30) # sleep before the calibrate, to make sure all preceeding repl communication has finished. In my tests 20ms was enough, make it 30ms to have some slack + # note: calibrate_rtc will interrupt the UART, means we temporarily lose REPL. the serial terminal in use may or may not succeed in reconnecting immediately/automatically, e.g. atom/pymakr self.calibrate_rtc() except Exception: pass @@ -271,10 +277,6 @@ def go_to_sleep(self, gps=True, pycom_module_off=True, accelerometer_off=True, w self.set_bits_in_memory(TRISB_ADDR, (1<<5) | (1<<4) ) self.set_bits_in_memory(ANSELB_ADDR, (1<<5) | (1<<4) ) - # actually only B4 and B5 - # todo: tris=1? - self.write_byte(ANSELB_ADDR, 0xff) - if wake_interrupt: # print("enable wake up PIC from RC1") self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin diff --git a/pysense-2/lib/pysense.py b/pysense-2/lib/pysense.py deleted file mode 100644 index b85c0d7..0000000 --- a/pysense-2/lib/pysense.py +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -# See https://docs.pycom.io for more information regarding library specifics - -from pycoproc import Pycoproc - -__version__ = '1.5.1' - -class Pysense(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, i2c, sda, scl) diff --git a/pysense-2/main.py b/pysense-2/main.py index 3b2dbda..543a6ac 100644 --- a/pysense-2/main.py +++ b/pysense-2/main.py @@ -8,25 +8,19 @@ # available at https://www.pycom.io/opensource/licensing # +# This script demonstrates two examples: +# * go to ultra low power mode (~10uA @3.75V) with all sensors, incl accelerometer and also pycom module (Fipy, Gpy, etc) off - tap the MCLR button for this +# * go to low power mode (~165uA @3.75V) with accelerometer on, pycom module in deepsleep and wake from accelerometer interrupt - hold the MCLR button down for this + # See https://docs.pycom.io for more information regarding library specifics import time import pycom import struct from machine import Pin -from pysense import Pysense +from pycoproc import Pycoproc import machine - from LIS2HH12 import LIS2HH12 -from SI7006A20 import SI7006A20 -from LTR329ALS01 import LTR329ALS01 -from MPL3115A2 import MPL3115A2,ALTITUDE,PRESSURE - -# This script demonstrates two examples: -# * go to ultra low power mode (~10uA @3.75V) with all sensors, incl accelerometer and also pycom module (Fipy, Gpy, etc) off -# * go to low power mode (~165uA @3.75V) with accelerometer on, pycom module in deepsleep and wake from accelerometer interrupt -wake_from_accelerometer = True -sleep_time_s = 300 def accelerometer(): print("ACCELEROMETER:", "accel:", accelerometer_sensor.acceleration(), "roll:", accelerometer_sensor.roll(), "pitch:", accelerometer_sensor.pitch(), "x/y/z:", accelerometer_sensor.x, accelerometer_sensor.y, accelerometer_sensor.z ) @@ -34,17 +28,15 @@ def accelerometer(): def activity_int_handler(pin_o): if pin_o(): print('[Activity]') - # blue - pycom.rgbled(0x00000A) + pycom.rgbled(0x00000A) # blue else: print('[Inactivity]') - # yellow - pycom.rgbled(0x0A0A00) + pycom.rgbled(0x0A0A00) # yellow def activity_int_handler_none(pin_o): pass -def blink(ct=5, color=0x220022, on_ms=100, off_ms=100 ): +def blink(color=0x0a0a0a, ct=5, on_ms=100, off_ms=100 ): while ct >= 0 : ct -= 1 pycom.rgbled(color) @@ -52,70 +44,119 @@ def blink(ct=5, color=0x220022, on_ms=100, off_ms=100 ): pycom.rgbled(0x000000) time.sleep_ms(off_ms) -def wait(color=0x0a0a0a): +def wait(color=0x0a0a0a, hold_timeout_ms=3000): + print(" - tap MCLR button to go to ultra low power mode (everything off)") + print(" - hold MCLR button down for", round(hold_timeout_ms/1000,1), "sec to go to low power mode and wake from accelerometer") print("wait for button ...") - blink(5, color) - pycom.rgbled(color) ct = 0 + pressed_time_ms = 0 + dot = '.' while True: if pycoproc.button_pressed(): - blink(5, color) - print("button pressed") - break + if pressed_time_ms == 0: + # the button just started to be pressed + pressed_time_ms = time.ticks_ms() + print("button pressed") + pycom.rgbled(color) + dot = '*' + else: + # the button is still being held down + if time.ticks_ms() - pressed_time_ms > hold_timeout_ms: + pycom.rgbled(0) + dot = '_' + else: + if pressed_time_ms != 0: + # the button was released + print("button released") + if time.ticks_ms() - pressed_time_ms > hold_timeout_ms: + return True + else: + return False time.sleep(0.1) ct += 1 if ct % 10 == 0: - print('.', end='') - pycom.rgbled(color) + print(dot, end='') + +def pretty_reset_cause(): + mrc = machine.reset_cause() + print('reset_cause', mrc, end=' ') + if mrc == machine.PWRON_RESET: + print("PWRON_RESET") + # plug in + # press reset button on module + # reset button on JTAG board + # core dump + elif mrc == machine.HARD_RESET: + print("HARD_RESET") + elif mrc == machine.WDT_RESET: + print("WDT_RESET") + # machine.reset() + elif mrc == machine.DEEPSLEEP_RESET: + print("DEEPSLEEP_RESET") + # machine.deepsleep() + elif mrc == machine.SOFT_RESET: + print("SOFT_RESET") + # Ctrl-D + elif mrc == machine.BROWN_OUT_RESET: + print("BROWN_OUT_RESET") + +def pretty_wake_reason(): + mwr = machine.wake_reason() + print("wake_reason", mwr, end=' ') + if mwr[0] == machine.PWRON_WAKE: + print("PWRON_WAKE") + # reset button + elif mwr[0] == machine.PIN_WAKE: + print("PIN_WAKE") + elif mwr[0] == machine.RTC_WAKE: + print("RTC_WAKE") + # from deepsleep + elif mwr[0] == machine.ULP_WAKE: + print("ULP_WAKE") + ############################################################### +sleep_time_s = 300 # 5 min pycom.heartbeat(False) -pycom.rgbled(0x0a0500) - -try: - print("lte deinit") - from network import LTE - lte = LTE() - lte.deinit() -except: - pass +pycom.rgbled(0x0a0a0a) # white +import binascii +import machine +print(os.uname().sysname.lower() + '-' + binascii.hexlify(machine.unique_id()).decode("utf-8")[-4:], "pysense2") -pycom.rgbled(0x0a0a0a) +pretty_wake_reason() +pretty_reset_cause() print("pycoproc init") -pycoproc = Pysense() - -b = pycoproc.read_battery_voltage() -print("battery {:.2f} V".format(b)) - -pycoproc.setup_sleep(sleep_time_s) - -wait(0x000a00) # blink green, wait for user to press MCLR button, blink green +pycoproc = Pycoproc() +print("battery {:.2f} V".format(pycoproc.read_battery_voltage())) +# init accelerometer accelerometer_sensor = LIS2HH12() +# read accelerometer sensor values accelerometer() +print("enable accelerometer interrupt") -if wake_from_accelerometer == True: - # configure accelerometer interrupt sensitivity - - # accelerometer_sensor.enable_activity_interrupt(8000, 200, activity_int_handler) # low sensitivty - # 2000mG (2G), 200ms - # accelerometer_sensor.enable_activity_interrupt(2000, 200, activity_int_handler) # medium sensitivity - accelerometer_sensor.enable_activity_interrupt( 100, 200, activity_int_handler) # high sensitivity - # accelerometer_sensor.enable_activity_interrupt(63, 160, activity_int_handler) # ultra sensitivty - - wait(0x0A000A) # blink purple, wait for user to press MCLR button, blink purple +# enable_activity_interrupt( [mG], [ms], callback) +# accelerometer_sensor.enable_activity_interrupt(8000, 200, activity_int_handler) # low sensitivty +# accelerometer_sensor.enable_activity_interrupt(2000, 200, activity_int_handler) # medium sensitivity +accelerometer_sensor.enable_activity_interrupt( 100, 200, activity_int_handler) # high sensitivity +# accelerometer_sensor.enable_activity_interrupt(63, 160, activity_int_handler) # ultra sensitivty +if wait(0x0A000A): # purple + print("button was held") + blink(0x000a00) # green print("enable pycom module to wake up from accelerometer interrupt") wake_pins = [Pin('P13', mode=Pin.IN, pull=Pin.PULL_DOWN)] machine.pin_sleep_wakeup(wake_pins, machine.WAKEUP_ANY_HIGH, True) - print("put pycoproc to sleep") + print("put pycoproc to sleep and pycom module to deepsleep for", round(sleep_time_s/60,1), "minutes") + pycoproc.setup_sleep(sleep_time_s) pycoproc.go_to_sleep(pycom_module_off=False, accelerometer_off=False, wake_interrupt=True) - - print("put pycom module to deepsleep", sleep_time_s, "s") machine.deepsleep(sleep_time_s * 1000) else: - print("put pycoproc to sleep, turn off everything") + print("button was tapped") + blink(0x100600) # orange + print("put pycoproc to sleep and turn pycom module off for", round(sleep_time_s/60,1), "minutes") + pycoproc.setup_sleep(sleep_time_s) pycoproc.go_to_sleep() print("we never reach here!") diff --git a/pysense-2/sensors.py b/pysense-2/pysense.py similarity index 96% rename from pysense-2/sensors.py rename to pysense-2/pysense.py index 695aa79..8b026dd 100644 --- a/pysense-2/sensors.py +++ b/pysense-2/pysense.py @@ -23,7 +23,7 @@ pycom.heartbeat(False) pycom.rgbled(0x0A0A08) # white -py = Pysense() +py = Pycoproc() mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals print("MPL3115A2 temperature: " + str(mp.temperature())) @@ -48,7 +48,3 @@ print("Pitch: " + str(li.pitch())) print("Battery voltage: " + str(py.read_battery_voltage())) - -time.sleep(3) -py.setup_sleep(10) -py.go_to_sleep() From 6c1cab8835c636b4d85c6429969e2dea482c9118 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Fri, 5 Feb 2021 13:17:25 +0100 Subject: [PATCH 05/39] it seems sometimes reading mclr button over i2c can fail, add retry loop --- pysense-2/lib/pycoproc.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/pysense-2/lib/pycoproc.py b/pysense-2/lib/pycoproc.py index d2480df..bf7ce03 100644 --- a/pysense-2/lib/pycoproc.py +++ b/pysense-2/lib/pycoproc.py @@ -320,8 +320,16 @@ def calibrate_rtc(self): time.sleep(0.5) def button_pressed(self): - button = self.read_bit(PORTA_ADDR, 3) - return not button + retry = 0 + while True: + try: + button = self.read_bit(PORTA_ADDR, 3) + return not button + except Exception as e: + if retry > 10: + raise Exception('Failed to read button state: {}'.format(e)) + print("Failed to read button state, retry ... ({}, {})".format(retry, e)) + retry += 1 def read_battery_voltage(self): self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) From 8f80c602e9ede6fb3c44e47bd0964d4dce2384ba Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 11:59:38 +0100 Subject: [PATCH 06/39] mv pysense-2 shields --- {pysense-2 => shields}/lib/LIS2HH12.py | 0 {pysense-2 => shields}/lib/LTR329ALS01.py | 0 {pysense-2 => shields}/lib/MPL3115A2.py | 0 {pysense-2 => shields}/lib/SI7006A20.py | 0 {pysense-2 => shields}/lib/pycoproc.py | 0 {pysense-2 => shields}/main.py | 0 {pysense-2 => shields}/pysense.py | 0 7 files changed, 0 insertions(+), 0 deletions(-) rename {pysense-2 => shields}/lib/LIS2HH12.py (100%) rename {pysense-2 => shields}/lib/LTR329ALS01.py (100%) rename {pysense-2 => shields}/lib/MPL3115A2.py (100%) rename {pysense-2 => shields}/lib/SI7006A20.py (100%) rename {pysense-2 => shields}/lib/pycoproc.py (100%) rename {pysense-2 => shields}/main.py (100%) rename {pysense-2 => shields}/pysense.py (100%) diff --git a/pysense-2/lib/LIS2HH12.py b/shields/lib/LIS2HH12.py similarity index 100% rename from pysense-2/lib/LIS2HH12.py rename to shields/lib/LIS2HH12.py diff --git a/pysense-2/lib/LTR329ALS01.py b/shields/lib/LTR329ALS01.py similarity index 100% rename from pysense-2/lib/LTR329ALS01.py rename to shields/lib/LTR329ALS01.py diff --git a/pysense-2/lib/MPL3115A2.py b/shields/lib/MPL3115A2.py similarity index 100% rename from pysense-2/lib/MPL3115A2.py rename to shields/lib/MPL3115A2.py diff --git a/pysense-2/lib/SI7006A20.py b/shields/lib/SI7006A20.py similarity index 100% rename from pysense-2/lib/SI7006A20.py rename to shields/lib/SI7006A20.py diff --git a/pysense-2/lib/pycoproc.py b/shields/lib/pycoproc.py similarity index 100% rename from pysense-2/lib/pycoproc.py rename to shields/lib/pycoproc.py diff --git a/pysense-2/main.py b/shields/main.py similarity index 100% rename from pysense-2/main.py rename to shields/main.py diff --git a/pysense-2/pysense.py b/shields/pysense.py similarity index 100% rename from pysense-2/pysense.py rename to shields/pysense.py From 39f0ac429da4850b6e20e64b767197b04204b892 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:03:11 +0100 Subject: [PATCH 07/39] mv v2 --- shields/lib/{pycoproc.py => pycoproc_2.py} | 0 shields/main.py | 2 +- shields/pysense.py | 2 +- 3 files changed, 2 insertions(+), 2 deletions(-) rename shields/lib/{pycoproc.py => pycoproc_2.py} (100%) diff --git a/shields/lib/pycoproc.py b/shields/lib/pycoproc_2.py similarity index 100% rename from shields/lib/pycoproc.py rename to shields/lib/pycoproc_2.py diff --git a/shields/main.py b/shields/main.py index 543a6ac..6fd28cb 100644 --- a/shields/main.py +++ b/shields/main.py @@ -18,7 +18,7 @@ import pycom import struct from machine import Pin -from pycoproc import Pycoproc +from pycoproc_2 import Pycoproc import machine from LIS2HH12 import LIS2HH12 diff --git a/shields/pysense.py b/shields/pysense.py index 8b026dd..cfa6280 100644 --- a/shields/pysense.py +++ b/shields/pysense.py @@ -12,7 +12,7 @@ import time import pycom -from pysense import Pysense +from pycoproc_2 import Pycoproc import machine from LIS2HH12 import LIS2HH12 From 11d9f5954735fcce3404e702b0164fe2b2e02a01 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:03:43 +0100 Subject: [PATCH 08/39] mv v2 --- shields/{pysense.py => pysense_2.py} | 0 shields/{main.py => shield_2.py} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename shields/{pysense.py => pysense_2.py} (100%) rename shields/{main.py => shield_2.py} (100%) diff --git a/shields/pysense.py b/shields/pysense_2.py similarity index 100% rename from shields/pysense.py rename to shields/pysense_2.py diff --git a/shields/main.py b/shields/shield_2.py similarity index 100% rename from shields/main.py rename to shields/shield_2.py From b9aeb7b8e62be0ae3aba2689cc8dc8c9cf16fdde Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:06:54 +0100 Subject: [PATCH 09/39] mv pytrack2 --- {pytrack-2 => shields}/lib/L76GNSS.py | 0 pytrack-2/main.py => shields/pytrack_2.py | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename {pytrack-2 => shields}/lib/L76GNSS.py (100%) rename pytrack-2/main.py => shields/pytrack_2.py (100%) diff --git a/pytrack-2/lib/L76GNSS.py b/shields/lib/L76GNSS.py similarity index 100% rename from pytrack-2/lib/L76GNSS.py rename to shields/lib/L76GNSS.py diff --git a/pytrack-2/main.py b/shields/pytrack_2.py similarity index 100% rename from pytrack-2/main.py rename to shields/pytrack_2.py From b2e9357bf9bd2b8c7ab6775de73d02b8eaac0183 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:13:20 +0100 Subject: [PATCH 10/39] fix pytrack2 --- shields/pytrack_2.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/shields/pytrack_2.py b/shields/pytrack_2.py index 1c20c9d..3f33ff5 100644 --- a/shields/pytrack_2.py +++ b/shields/pytrack_2.py @@ -19,7 +19,7 @@ from machine import RTC from machine import SD from L76GNSS import L76GNSS -from pytrack import Pytrack +from pycoproc_2 import Pycoproc pycom.heartbeat(False) pycom.rgbled(0x0A0A08) # white @@ -35,7 +35,7 @@ utime.timezone(7200) print('Adjusted from UTC to EST timezone', utime.localtime(), '\n') -py = Pytrack() +py = Pycoproc() time.sleep(1) l76 = L76GNSS(py, timeout=30, buffer=512) From 563d4cc73f5ce074d652adb88a2cbd87553ccbbd Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:13:55 +0100 Subject: [PATCH 11/39] pycoproc_2 v0.05: supports pytrack-2 and pysense-2 --- shields/lib/pycoproc_2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shields/lib/pycoproc_2.py b/shields/lib/pycoproc_2.py index bf7ce03..94cff44 100644 --- a/shields/lib/pycoproc_2.py +++ b/shields/lib/pycoproc_2.py @@ -15,7 +15,7 @@ import time import pycom -__version__ = '0.0.4' +__version__ = '0.0.5' """ PIC MCU wakeup reason types """ WAKE_REASON_ACCELEROMETER = 1 From 959754c3ddce361b9a29ee69014d387d7cacf30e Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:14:28 +0100 Subject: [PATCH 12/39] rm pytrack-2 --- pytrack-2/lib/LIS2HH12.py | 178 --------------------- pytrack-2/lib/pycoproc.py | 326 -------------------------------------- pytrack-2/lib/pytrack.py | 18 --- 3 files changed, 522 deletions(-) delete mode 100644 pytrack-2/lib/LIS2HH12.py delete mode 100644 pytrack-2/lib/pycoproc.py delete mode 100644 pytrack-2/lib/pytrack.py diff --git a/pytrack-2/lib/LIS2HH12.py b/pytrack-2/lib/LIS2HH12.py deleted file mode 100644 index fffa757..0000000 --- a/pytrack-2/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (threshold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (threshold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used threshold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pytrack-2/lib/pycoproc.py b/pytrack-2/lib/pycoproc.py deleted file mode 100644 index 83a0ad8..0000000 --- a/pytrack-2/lib/pycoproc.py +++ /dev/null @@ -1,326 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -# See https://docs.pycom.io for more information regarding library specifics - -from machine import Pin -from machine import I2C -import time -import pycom - -__version__ = '0.0.4' - -""" PIC MCU wakeup reason types """ -WAKE_REASON_ACCELEROMETER = 1 -WAKE_REASON_PUSH_BUTTON = 2 -WAKE_REASON_TIMER = 4 -WAKE_REASON_INT_PIN = 8 - -class Pycoproc: - """ class for handling the interaction with PIC MCU """ - - I2C_SLAVE_ADDR = const(8) - - CMD_PEEK = const(0x0) - CMD_POKE = const(0x01) - CMD_MAGIC = const(0x02) - CMD_HW_VER = const(0x10) - CMD_FW_VER = const(0x11) - CMD_PROD_ID = const(0x12) - CMD_SETUP_SLEEP = const(0x20) - CMD_GO_SLEEP = const(0x21) - CMD_CALIBRATE = const(0x22) - CMD_BAUD_CHANGE = const(0x30) - CMD_DFU = const(0x31) - CMD_RESET = const(0x40) - - REG_CMD = const(0) - REG_ADDRL = const(1) - REG_ADDRH = const(2) - REG_AND = const(3) - REG_OR = const(4) - REG_XOR = const(5) - - ANSELA_ADDR = const(0x18C) - ANSELB_ADDR = const(0x18D) - ANSELC_ADDR = const(0x18E) - - ADCON0_ADDR = const(0x9D) - ADCON1_ADDR = const(0x9E) - - IOCAP_ADDR = const(0x391) - IOCAN_ADDR = const(0x392) - - INTCON_ADDR = const(0x0B) - OPTION_REG_ADDR = const(0x95) - - _ADCON0_CHS_POSN = const(0x02) - _ADCON0_ADON_MASK = const(0x01) - _ADCON1_ADCS_POSN = const(0x04) - _ADCON0_GO_nDONE_MASK = const(0x02) - - ADRESL_ADDR = const(0x09B) - ADRESH_ADDR = const(0x09C) - - TRISA_ADDR = const(0x08C) - TRISC_ADDR = const(0x08E) - - PORTA_ADDR = const(0x00C) - PORTC_ADDR = const(0x00E) - - WPUA_ADDR = const(0x20C) - - WAKE_REASON_ADDR = const(0x064C) - MEMORY_BANK_ADDR = const(0x0620) - - PCON_ADDR = const(0x096) - STATUS_ADDR = const(0x083) - - EXP_RTC_PERIOD = const(7000) - - def __init__(self, i2c=None, sda='P22', scl='P21'): - if i2c is not None: - self.i2c = i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl), baudrate=100000) - - self.sda = sda - self.scl = scl - self.clk_cal_factor = 1 - self.reg = bytearray(6) - self.wake_int = False - self.wake_int_pin = False - self.wake_int_pin_rising_edge = True - - # Make sure we are inserted into the - # correct board and can talk to the PIC - try: - self.read_fw_version() - except Exception as e: - raise Exception('Board not detected: {}'.format(e)) - - # init the ADC for the battery measurements - self.poke_memory(ANSELC_ADDR, 1 << 2) - self.poke_memory(ADCON0_ADDR, (0x06 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) - self.poke_memory(ADCON1_ADDR, (0x06 << _ADCON1_ADCS_POSN)) - # enable the pull-up on RA3 - self.poke_memory(WPUA_ADDR, (1 << 3)) - - # set RC6 and RC7 as outputs and enable power to the sensors and the GPS - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 6)) - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - - - self.gps_standby(False) - self.sensor_power() - self.sd_power() - - # for Pysense/Pytrack 2.0, the minimum firmware version is 15 - if self.read_fw_version() < 15: - raise ValueError('Firmware out of date') - - - def _write(self, data, wait=True): - self.i2c.writeto(I2C_SLAVE_ADDR, data) - if wait: - self._wait() - - def _read(self, size): - return self.i2c.readfrom(I2C_SLAVE_ADDR, size + 1)[1:(size + 1)] - - def _wait(self): - count = 0 - time.sleep_us(10) - while self.i2c.readfrom(I2C_SLAVE_ADDR, 1)[0] != 0xFF: - time.sleep_us(100) - count += 1 - if (count > 500): # timeout after 50ms - raise Exception('Board timeout') - - def _send_cmd(self, cmd): - self._write(bytes([cmd])) - - def read_hw_version(self): - self._send_cmd(CMD_HW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_fw_version(self): - self._send_cmd(CMD_FW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_product_id(self): - self._send_cmd(CMD_PROD_ID) - d = self._read(2) - return (d[1] << 8) + d[0] - - def peek_memory(self, addr): - self._write(bytes([CMD_PEEK, addr & 0xFF, (addr >> 8) & 0xFF])) - return self._read(1)[0] - - def poke_memory(self, addr, value): - self._write(bytes([CMD_POKE, addr & 0xFF, (addr >> 8) & 0xFF, value & 0xFF])) - - def magic_write_read(self, addr, _and=0xFF, _or=0, _xor=0): - self._write(bytes([CMD_MAGIC, addr & 0xFF, (addr >> 8) & 0xFF, _and & 0xFF, _or & 0xFF, _xor & 0xFF])) - return self._read(1)[0] - - def toggle_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _xor=bits) - - def mask_bits_in_memory(self, addr, mask): - self.magic_write_read(addr, _and=mask) - - def set_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _or=bits) - - def setup_sleep(self, time_s): - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_s * self.clk_cal_factor) + 0.5) # round to the nearest integer - if time_s >= 2**(8*3): - time_s = 2**(8*3)-1 - self._write(bytes([CMD_SETUP_SLEEP, time_s & 0xFF, (time_s >> 8) & 0xFF, (time_s >> 16) & 0xFF])) - - def go_to_sleep(self, gps=True): - self.gps_standby(gps) - self.sensor_power(False) - self.sd_power(False) - - # disable the ADC - self.poke_memory(ADCON0_ADDR, 0) - - if self.wake_int: - # Don't touch RA3, RA5 or RC1 so that interrupt wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~((1 << 6) | (1 << 7) | (1 << 1))) - else: - # disable power to the accelerometer, and don't touch RA3 so that button wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~(0)) - - self.poke_memory(ANSELB_ADDR, 0xFF) - - # check if INT pin (PIC RC1), should be used for wakeup - if self.wake_int_pin: - if self.wake_int_pin_rising_edge: - self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin - else: - self.mask_bits_in_memory(OPTION_REG_ADDR, ~(1 << 6)) # falling edge of INT pin - self.mask_bits_in_memory(ANSELC_ADDR, ~(1 << 1)) # disable analog function for RC1 pin - self.set_bits_in_memory(TRISC_ADDR, 1 << 1) # make RC1 input pin - self.mask_bits_in_memory(INTCON_ADDR, ~(1 << 1)) # clear INTF - self.set_bits_in_memory(INTCON_ADDR, 1 << 4) # enable interrupt; set INTE) - - self._write(bytes([CMD_GO_SLEEP]), wait=False) - - def calibrate_rtc(self): - # the 1.024 factor is because the PIC LF operates at 31 KHz - # WDT has a frequency divider to generate 1 ms - # and then there is a binary prescaler, e.g., 1, 2, 4 ... 512, 1024 ms - # hence the need for the constant - self._write(bytes([CMD_CALIBRATE]), wait=False) - self.i2c.deinit() - Pin('P21', mode=Pin.IN) - pulses = pycom.pulses_get('P21', 100) - self.i2c.init(mode=I2C.MASTER, pins=(self.sda, self.scl), baudrate=100000) - idx = 0 - for i in range(len(pulses)): - if pulses[i][1] > EXP_RTC_PERIOD: - idx = i - break - try: - period = pulses[idx][1] - pulses[(idx - 1)][1] - except: - period = 0 - if period > 0: - self.clk_cal_factor = (EXP_RTC_PERIOD / period) * (1000 / 1024) - if self.clk_cal_factor > 1.25 or self.clk_cal_factor < 0.75: - self.clk_cal_factor = 1 - - def button_pressed(self): - button = self.peek_memory(PORTA_ADDR) & (1 << 3) - return not button - - def read_battery_voltage(self): - self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) - time.sleep_us(50) - while self.peek_memory(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: - time.sleep_us(100) - adc_val = (self.peek_memory(ADRESH_ADDR) << 2) + (self.peek_memory(ADRESL_ADDR) >> 6) - return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET - - def setup_int_wake_up(self, rising, falling): - """ rising is for activity detection, falling for inactivity """ - wake_int = False - if rising: - self.set_bits_in_memory(IOCAP_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAP_ADDR, ~(1 << 5)) - - if falling: - self.set_bits_in_memory(IOCAN_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAN_ADDR, ~(1 << 5)) - self.wake_int = wake_int - - def setup_int_pin_wake_up(self, rising_edge = True): - """ allows wakeup to be made by the INT pin (PIC -RC1) """ - self.wake_int_pin = True - self.wake_int_pin_rising_edge = rising_edge - - def gps_standby(self, enabled=True): - - if enabled: - # make RC4 input - self.set_bits_in_memory(TRISC_ADDR, 1 << 4) - else: - # make RC4 an output - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 4)) - # drive RC4 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 4) - time.sleep(0.2) - # drive RC4 low - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 4)) - time.sleep(0.2) - # drive RC4 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 4) - time.sleep(0.2) - - def sensor_power(self, enabled=True): - # make RC7 an output - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - if enabled: - # drive RC7 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) - else: - # drive RC7 low - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) - - def sd_power(self, enabled=True): - # make RA5 an output - self.mask_bits_in_memory(TRISA_ADDR, ~(1 << 5)) - if enabled: - # drive RA5 high - self.set_bits_in_memory(PORTA_ADDR, 1 << 5) - else: - # drive RA5 low - self.mask_bits_in_memory(PORTA_ADDR, ~(1 << 5)) - - - # at the end: - def reset_cmd(self): - self._send_cmd(CMD_RESET) - return diff --git a/pytrack-2/lib/pytrack.py b/pytrack-2/lib/pytrack.py deleted file mode 100644 index 5558f5f..0000000 --- a/pytrack-2/lib/pytrack.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from pycoproc import Pycoproc - -__version__ = '1.5.1' - -class Pytrack(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, i2c, sda, scl) From 14d0ee87c0131cd2b220ecf63b99901da67607f7 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:21:45 +0100 Subject: [PATCH 13/39] mv pyscan --- pyscan/lib/LIS2HH12.py | 178 ----------------------- pyscan/lib/LTR329ALS01.py | 80 ---------- pyscan/lib/pyscan.py | 18 --- {pyscan => shields}/lib/MFRC630.mpy | Bin {pyscan => shields}/lib/MFRC630.mpy-1.18 | Bin pyscan/main.py => shields/pyscan_1.py | 0 pyscan/nfc.py => shields/pyscan_1_nfc.py | 0 7 files changed, 276 deletions(-) delete mode 100644 pyscan/lib/LIS2HH12.py delete mode 100644 pyscan/lib/LTR329ALS01.py delete mode 100644 pyscan/lib/pyscan.py rename {pyscan => shields}/lib/MFRC630.mpy (100%) rename {pyscan => shields}/lib/MFRC630.mpy-1.18 (100%) rename pyscan/main.py => shields/pyscan_1.py (100%) rename pyscan/nfc.py => shields/pyscan_1_nfc.py (100%) diff --git a/pyscan/lib/LIS2HH12.py b/pyscan/lib/LIS2HH12.py deleted file mode 100644 index 49a6b5a..0000000 --- a/pyscan/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (thresold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (thresold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used thresold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pyscan/lib/LTR329ALS01.py b/pyscan/lib/LTR329ALS01.py deleted file mode 100644 index 49e3439..0000000 --- a/pyscan/lib/LTR329ALS01.py +++ /dev/null @@ -1,80 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C - -class LTR329ALS01: - ALS_I2CADDR = const(0x29) # The device's I2C address - - ALS_CONTR_REG = const(0x80) - ALS_MEAS_RATE_REG = const(0x85) - - ALS_DATA_CH1_LOW = const(0x88) - ALS_DATA_CH1_HIGH = const(0x89) - ALS_DATA_CH0_LOW = const(0x8A) - ALS_DATA_CH0_HIGH = const(0x8B) - - ALS_GAIN_1X = const(0x00) - ALS_GAIN_2X = const(0x01) - ALS_GAIN_4X = const(0x02) - ALS_GAIN_8X = const(0x03) - ALS_GAIN_48X = const(0x06) - ALS_GAIN_96X = const(0x07) - - ALS_INT_50 = const(0x01) - ALS_INT_100 = const(0x00) - ALS_INT_150 = const(0x04) - ALS_INT_200 = const(0x02) - ALS_INT_250 = const(0x05) - ALS_INT_300 = const(0x06) - ALS_INT_350 = const(0x07) - ALS_INT_400 = const(0x03) - - ALS_RATE_50 = const(0x00) - ALS_RATE_100 = const(0x01) - ALS_RATE_200 = const(0x02) - ALS_RATE_500 = const(0x03) - ALS_RATE_1000 = const(0x04) - ALS_RATE_2000 = const(0x05) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21', gain = ALS_GAIN_1X, integration = ALS_INT_100, rate = ALS_RATE_500): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - contr = self._getContr(gain) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_CONTR_REG, bytearray([contr])) - - measrate = self._getMeasRate(integration, rate) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_MEAS_RATE_REG, bytearray([measrate])) - - time.sleep(0.01) - - def _getContr(self, gain): - return ((gain & 0x07) << 2) + 0x01 - - def _getMeasRate(self, integration, rate): - return ((integration & 0x07) << 3) + (rate & 0x07) - - def _getWord(self, high, low): - return ((high & 0xFF) << 8) + (low & 0xFF) - - def light(self): - ch1low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_LOW, 1) - ch1high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_HIGH, 1) - data1 = int(self._getWord(ch1high[0], ch1low[0])) - - ch0low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_LOW, 1) - ch0high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_HIGH, 1) - data0 = int(self._getWord(ch0high[0], ch0low[0])) - - return (data0, data1) diff --git a/pyscan/lib/pyscan.py b/pyscan/lib/pyscan.py deleted file mode 100644 index 0e956c7..0000000 --- a/pyscan/lib/pyscan.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from pycoproc import Pycoproc - -__version__ = '1.0.1' - -class Pyscan(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, Pycoproc.PYSCAN, i2c, sda, scl) diff --git a/pyscan/lib/MFRC630.mpy b/shields/lib/MFRC630.mpy similarity index 100% rename from pyscan/lib/MFRC630.mpy rename to shields/lib/MFRC630.mpy diff --git a/pyscan/lib/MFRC630.mpy-1.18 b/shields/lib/MFRC630.mpy-1.18 similarity index 100% rename from pyscan/lib/MFRC630.mpy-1.18 rename to shields/lib/MFRC630.mpy-1.18 diff --git a/pyscan/main.py b/shields/pyscan_1.py similarity index 100% rename from pyscan/main.py rename to shields/pyscan_1.py diff --git a/pyscan/nfc.py b/shields/pyscan_1_nfc.py similarity index 100% rename from pyscan/nfc.py rename to shields/pyscan_1_nfc.py From acf04accff1c55405300c7b04cd7f61383dff323 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:22:25 +0100 Subject: [PATCH 14/39] mv pycoproc1 --- lib/pycoproc/pycoproc-2.py | 345 ------------------ .../pycoproc.py => shields/lib/pycoproc_1.py | 0 2 files changed, 345 deletions(-) delete mode 100644 lib/pycoproc/pycoproc-2.py rename lib/pycoproc/pycoproc.py => shields/lib/pycoproc_1.py (100%) diff --git a/lib/pycoproc/pycoproc-2.py b/lib/pycoproc/pycoproc-2.py deleted file mode 100644 index 34a9079..0000000 --- a/lib/pycoproc/pycoproc-2.py +++ /dev/null @@ -1,345 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -# See https://docs.pycom.io for more information regarding library specifics - -from machine import Pin -from machine import I2C -import time -import pycom - -__version__ = '0.0.3' - -""" PIC MCU wakeup reason types """ -WAKE_REASON_ACCELEROMETER = 1 -WAKE_REASON_PUSH_BUTTON = 2 -WAKE_REASON_TIMER = 4 -WAKE_REASON_INT_PIN = 8 - -class Pycoproc: - """ class for handling the interaction with PIC MCU """ - - I2C_SLAVE_ADDR = const(8) - - PYSENSE = const(1) - PYTRACK = const(2) - PYSCAN = const(3) - - BOARD_TYPE_SET = (PYSENSE, PYTRACK, PYSCAN) - - CMD_PEEK = const(0x0) - CMD_POKE = const(0x01) - CMD_MAGIC = const(0x02) - CMD_HW_VER = const(0x10) - CMD_FW_VER = const(0x11) - CMD_PROD_ID = const(0x12) - CMD_SETUP_SLEEP = const(0x20) - CMD_GO_SLEEP = const(0x21) - CMD_CALIBRATE = const(0x22) - CMD_BAUD_CHANGE = const(0x30) - CMD_DFU = const(0x31) - CMD_RESET = const(0x40) - - REG_CMD = const(0) - REG_ADDRL = const(1) - REG_ADDRH = const(2) - REG_AND = const(3) - REG_OR = const(4) - REG_XOR = const(5) - - ANSELA_ADDR = const(0x18C) - ANSELB_ADDR = const(0x18D) - ANSELC_ADDR = const(0x18E) - - ADCON0_ADDR = const(0x9D) - ADCON1_ADDR = const(0x9E) - - IOCAP_ADDR = const(0x391) - IOCAN_ADDR = const(0x392) - - INTCON_ADDR = const(0x0B) - OPTION_REG_ADDR = const(0x95) - - _ADCON0_CHS_POSN = const(0x02) - _ADCON0_ADON_MASK = const(0x01) - _ADCON1_ADCS_POSN = const(0x04) - _ADCON0_GO_nDONE_MASK = const(0x02) - - ADRESL_ADDR = const(0x09B) - ADRESH_ADDR = const(0x09C) - - TRISA_ADDR = const(0x08C) - TRISC_ADDR = const(0x08E) - - PORTA_ADDR = const(0x00C) - PORTC_ADDR = const(0x00E) - - WPUA_ADDR = const(0x20C) - - WAKE_REASON_ADDR = const(0x064C) - MEMORY_BANK_ADDR = const(0x0620) - - PCON_ADDR = const(0x096) - STATUS_ADDR = const(0x083) - - EXP_RTC_PERIOD = const(7000) - - def __init__(self, i2c=None, sda='P22', scl='P21'): - if i2c is not None: - self.i2c = i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl), baudrate=100000) - - self.sda = sda - self.scl = scl - self.clk_cal_factor = 1 - self.reg = bytearray(6) - self.wake_int = False - self.wake_int_pin = False - self.wake_int_pin_rising_edge = True - - # Make sure we are inserted into the - # correct board and can talk to the PIC - try: - self.read_fw_version() - except Exception as e: - raise Exception('Board not detected: {}'.format(e)) - - # init the ADC for the battery measurements - self.poke_memory(ANSELC_ADDR, 1 << 2) - self.poke_memory(ADCON0_ADDR, (0x06 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) - self.poke_memory(ADCON1_ADDR, (0x06 << _ADCON1_ADCS_POSN)) - # enable the pull-up on RA3 - self.poke_memory(WPUA_ADDR, (1 << 3)) - # make RC5 an input - self.set_bits_in_memory(TRISC_ADDR, 1 << 5) - # set RC6 and RC7 as outputs and enable power to the sensors and the GPS - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 6)) - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - - - self.gps_standby(False) - self.sensor_power() - self.sd_power() - - if self.read_fw_version() < 6: - raise ValueError('Firmware out of date') - - - def _write(self, data, wait=True): - self.i2c.writeto(I2C_SLAVE_ADDR, data) - if wait: - self._wait() - - def _read(self, size): - return self.i2c.readfrom(I2C_SLAVE_ADDR, size + 1)[1:(size + 1)] - - def _wait(self): - count = 0 - time.sleep_us(10) - while self.i2c.readfrom(I2C_SLAVE_ADDR, 1)[0] != 0xFF: - time.sleep_us(100) - count += 1 - if (count > 500): # timeout after 50ms - raise Exception('Board timeout') - - def _send_cmd(self, cmd): - self._write(bytes([cmd])) - - def read_hw_version(self): - self._send_cmd(CMD_HW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_fw_version(self): - self._send_cmd(CMD_FW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_product_id(self): - self._send_cmd(CMD_PROD_ID) - d = self._read(2) - return (d[1] << 8) + d[0] - - def peek_memory(self, addr): - self._write(bytes([CMD_PEEK, addr & 0xFF, (addr >> 8) & 0xFF])) - return self._read(1)[0] - - def poke_memory(self, addr, value): - self._write(bytes([CMD_POKE, addr & 0xFF, (addr >> 8) & 0xFF, value & 0xFF])) - - def magic_write_read(self, addr, _and=0xFF, _or=0, _xor=0): - self._write(bytes([CMD_MAGIC, addr & 0xFF, (addr >> 8) & 0xFF, _and & 0xFF, _or & 0xFF, _xor & 0xFF])) - return self._read(1)[0] - - def toggle_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _xor=bits) - - def mask_bits_in_memory(self, addr, mask): - self.magic_write_read(addr, _and=mask) - - def set_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _or=bits) - - def get_wake_reason(self): - """ returns the wakeup reason, a value out of constants WAKE_REASON_* """ - return self.peek_memory(WAKE_REASON_ADDR) - - def get_sleep_remaining(self): - """ returns the remaining time from sleep, as an interrupt (wakeup source) might have triggered """ - c3 = self.peek_memory(WAKE_REASON_ADDR + 3) - c2 = self.peek_memory(WAKE_REASON_ADDR + 2) - c1 = self.peek_memory(WAKE_REASON_ADDR + 1) - time_device_s = (c3 << 16) + (c2 << 8) + c1 - # this time is from PIC internal oscilator, so it needs to be adjusted with the calibration value - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_device_s / self.clk_cal_factor) + 0.5) # 0.5 used for round - return time_s - - def setup_sleep(self, time_s): - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_s * self.clk_cal_factor) + 0.5) # round to the nearest integer - if time_s >= 2**(8*3): - time_s = 2**(8*3)-1 - self._write(bytes([CMD_SETUP_SLEEP, time_s & 0xFF, (time_s >> 8) & 0xFF, (time_s >> 16) & 0xFF])) - - def go_to_sleep(self, gps=True): - # enable or disable back-up power to the GPS receiver - if gps: - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) - else: - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) - # disable the ADC - self.poke_memory(ADCON0_ADDR, 0) - - if self.wake_int: - # Don't touch RA3, RA5 or RC1 so that interrupt wake-up works - self.poke_memory(ANSELA_ADDR, ~((1 << 3) | (1 << 5))) - self.poke_memory(ANSELC_ADDR, ~((1 << 6) | (1 << 7) | (1 << 1))) - else: - # disable power to the accelerometer, and don't touch RA3 so that button wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~(1 << 7)) - - self.poke_memory(ANSELB_ADDR, 0xFF) - - # check if INT pin (PIC RC1), should be used for wakeup - if self.wake_int_pin: - if self.wake_int_pin_rising_edge: - self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin - else: - self.mask_bits_in_memory(OPTION_REG_ADDR, ~(1 << 6)) # falling edge of INT pin - self.mask_bits_in_memory(ANSELC_ADDR, ~(1 << 1)) # disable analog function for RC1 pin - self.set_bits_in_memory(TRISC_ADDR, 1 << 1) # make RC1 input pin - self.mask_bits_in_memory(INTCON_ADDR, ~(1 << 1)) # clear INTF - self.set_bits_in_memory(INTCON_ADDR, 1 << 4) # enable interrupt; set INTE) - - self._write(bytes([CMD_GO_SLEEP]), wait=False) - # kill the run pin - Pin('P3', mode=Pin.OUT, value=0) - - def calibrate_rtc(self): - # the 1.024 factor is because the PIC LF operates at 31 KHz - # WDT has a frequency divider to generate 1 ms - # and then there is a binary prescaler, e.g., 1, 2, 4 ... 512, 1024 ms - # hence the need for the constant - self._write(bytes([CMD_CALIBRATE]), wait=False) - self.i2c.deinit() - Pin('P21', mode=Pin.IN) - pulses = pycom.pulses_get('P21', 100) - self.i2c.init(mode=I2C.MASTER, pins=(self.sda, self.scl), baudrate=100000) - idx = 0 - for i in range(len(pulses)): - if pulses[i][1] > EXP_RTC_PERIOD: - idx = i - break - try: - period = pulses[idx][1] - pulses[(idx - 1)][1] - except: - period = 0 - if period > 0: - self.clk_cal_factor = (EXP_RTC_PERIOD / period) * (1000 / 1024) - if self.clk_cal_factor > 1.25 or self.clk_cal_factor < 0.75: - self.clk_cal_factor = 1 - - def button_pressed(self): - button = self.peek_memory(PORTA_ADDR) & (1 << 3) - return not button - - def read_battery_voltage(self): - self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) - time.sleep_us(50) - while self.peek_memory(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: - time.sleep_us(100) - adc_val = (self.peek_memory(ADRESH_ADDR) << 2) + (self.peek_memory(ADRESL_ADDR) >> 6) - return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET - - def setup_int_wake_up(self, rising, falling): - """ rising is for activity detection, falling for inactivity """ - wake_int = False - if rising: - self.set_bits_in_memory(IOCAP_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAP_ADDR, ~(1 << 5)) - - if falling: - self.set_bits_in_memory(IOCAN_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAN_ADDR, ~(1 << 5)) - self.wake_int = wake_int - - def setup_int_pin_wake_up(self, rising_edge = True): - """ allows wakeup to be made by the INT pin (PIC -RC1) """ - self.wake_int_pin = True - self.wake_int_pin_rising_edge = rising_edge - - def gps_standby(self, enabled=True): - # make RC4 an output - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 4)) - if enabled: - # drive RC4 low - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 4)) - else: - # drive RC4 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 4) - - def sensor_power(self, enabled=True): - # make RC7 an output - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - if enabled: - # drive RC7 high - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) - else: - # drive RC7 low - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) - - def sd_power(self, enabled=True): - # make RA5 an output - self.mask_bits_in_memory(TRISA_ADDR, ~(1 << 5)) - if enabled: - # drive RA5 high - self.set_bits_in_memory(PORTA_ADDR, 1 << 5) - else: - # drive RA5 low - self.mask_bits_in_memory(PORTA_ADDR, ~(1 << 5)) - - - # at the end: - def reset_cmd(self): - self._send_cmd(CMD_RESET) - return diff --git a/lib/pycoproc/pycoproc.py b/shields/lib/pycoproc_1.py similarity index 100% rename from lib/pycoproc/pycoproc.py rename to shields/lib/pycoproc_1.py From f5806ccccf1b4e3979f7253787eb0c48e8870acd Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:26:58 +0100 Subject: [PATCH 15/39] fix pyscan --- shields/pyscan_1.py | 4 ++-- shields/pyscan_1_nfc.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/shields/pyscan_1.py b/shields/pyscan_1.py index 945665e..66ab94e 100644 --- a/shields/pyscan_1.py +++ b/shields/pyscan_1.py @@ -10,7 +10,7 @@ DEBUG = False # change to True to see debug messages -from pyscan import Pyscan +from pycoproc_1 import Pycoproc from MFRC630 import MFRC630 from LIS2HH12 import LIS2HH12 from LTR329ALS01 import LTR329ALS01 @@ -23,7 +23,7 @@ [0x43, 0x95, 0xDD, 0xF9], [0x46, 0x5A, 0xEB, 0x7D, 0x8A, 0x08, 0x04]] -py = Pyscan() +py = Pycoproc(Pycoproc.PYSCAN) nfc = MFRC630(py) lt = LTR329ALS01(py) li = LIS2HH12(py) diff --git a/shields/pyscan_1_nfc.py b/shields/pyscan_1_nfc.py index d4ccc4f..6b2ea36 100644 --- a/shields/pyscan_1_nfc.py +++ b/shields/pyscan_1_nfc.py @@ -8,7 +8,7 @@ If authentication succeeds will attempt to read sectors from the card ''' -from pyscan import Pyscan +from pycoproc_1 import Pycoproc from MFRC630 import MFRC630 import time import pycom @@ -17,7 +17,7 @@ CARDkey = [ 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF ] DECODE_CARD = False -py = Pyscan() +py = Pycoproc(Pycoproc.PYSCAN) nfc = MFRC630(py) RGB_BRIGHTNESS = 0x8 From f7b18ac1a686dc4b9a7924f2b94983046145737b Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:28:20 +0100 Subject: [PATCH 16/39] mv pysense1 --- pysense/lib/LIS2HH12.py | 178 ------------------------ pysense/lib/LTR329ALS01.py | 80 ----------- pysense/lib/MPL3115A2.py | 129 ----------------- pysense/lib/SI7006A20.py | 118 ---------------- pysense/lib/pysense.py | 20 --- pysense/main.py => shields/pysense_1.py | 0 6 files changed, 525 deletions(-) delete mode 100644 pysense/lib/LIS2HH12.py delete mode 100644 pysense/lib/LTR329ALS01.py delete mode 100644 pysense/lib/MPL3115A2.py delete mode 100644 pysense/lib/SI7006A20.py delete mode 100644 pysense/lib/pysense.py rename pysense/main.py => shields/pysense_1.py (100%) diff --git a/pysense/lib/LIS2HH12.py b/pysense/lib/LIS2HH12.py deleted file mode 100644 index fffa757..0000000 --- a/pysense/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (threshold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (threshold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used threshold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pysense/lib/LTR329ALS01.py b/pysense/lib/LTR329ALS01.py deleted file mode 100644 index 9087156..0000000 --- a/pysense/lib/LTR329ALS01.py +++ /dev/null @@ -1,80 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C - -class LTR329ALS01: - ALS_I2CADDR = const(0x29) # The device's I2C address - - ALS_CONTR_REG = const(0x80) - ALS_MEAS_RATE_REG = const(0x85) - - ALS_DATA_CH1_LOW = const(0x88) - ALS_DATA_CH1_HIGH = const(0x89) - ALS_DATA_CH0_LOW = const(0x8A) - ALS_DATA_CH0_HIGH = const(0x8B) - - ALS_GAIN_1X = const(0x00) - ALS_GAIN_2X = const(0x01) - ALS_GAIN_4X = const(0x02) - ALS_GAIN_8X = const(0x03) - ALS_GAIN_48X = const(0x06) - ALS_GAIN_96X = const(0x07) - - ALS_INT_50 = const(0x01) - ALS_INT_100 = const(0x00) - ALS_INT_150 = const(0x04) - ALS_INT_200 = const(0x02) - ALS_INT_250 = const(0x05) - ALS_INT_300 = const(0x06) - ALS_INT_350 = const(0x07) - ALS_INT_400 = const(0x03) - - ALS_RATE_50 = const(0x00) - ALS_RATE_100 = const(0x01) - ALS_RATE_200 = const(0x02) - ALS_RATE_500 = const(0x03) - ALS_RATE_1000 = const(0x04) - ALS_RATE_2000 = const(0x05) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21', gain = ALS_GAIN_1X, integration = ALS_INT_100, rate = ALS_RATE_500): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - contr = self._getContr(gain) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_CONTR_REG, bytearray([contr])) - - measrate = self._getMeasRate(integration, rate) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_MEAS_RATE_REG, bytearray([measrate])) - - time.sleep(0.01) - - def _getContr(self, gain): - return ((gain & 0x07) << 2) + 0x01 - - def _getMeasRate(self, integration, rate): - return ((integration & 0x07) << 3) + (rate & 0x07) - - def _getWord(self, high, low): - return ((high & 0xFF) << 8) + (low & 0xFF) - - def light(self): - ch1low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_LOW, 1) - ch1high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_HIGH, 1) - data1 = int(self._getWord(ch1high[0], ch1low[0])) - - ch0low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_LOW, 1) - ch0high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_HIGH, 1) - data0 = int(self._getWord(ch0high[0], ch0low[0])) - - return (data0, data1) diff --git a/pysense/lib/MPL3115A2.py b/pysense/lib/MPL3115A2.py deleted file mode 100644 index b0a44c7..0000000 --- a/pysense/lib/MPL3115A2.py +++ /dev/null @@ -1,129 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C - -ALTITUDE = const(0) -PRESSURE = const(1) - -class MPL3115A2exception(Exception): - pass - -class MPL3115A2: - MPL3115_I2CADDR = const(0x60) - MPL3115_STATUS = const(0x00) - MPL3115_PRESSURE_DATA_MSB = const(0x01) - MPL3115_PRESSURE_DATA_CSB = const(0x02) - MPL3115_PRESSURE_DATA_LSB = const(0x03) - MPL3115_TEMP_DATA_MSB = const(0x04) - MPL3115_TEMP_DATA_LSB = const(0x05) - MPL3115_DR_STATUS = const(0x06) - MPL3115_DELTA_DATA = const(0x07) - MPL3115_WHO_AM_I = const(0x0c) - MPL3115_FIFO_STATUS = const(0x0d) - MPL3115_FIFO_DATA = const(0x0e) - MPL3115_FIFO_SETUP = const(0x0e) - MPL3115_TIME_DELAY = const(0x10) - MPL3115_SYS_MODE = const(0x11) - MPL3115_INT_SORCE = const(0x12) - MPL3115_PT_DATA_CFG = const(0x13) - MPL3115_BAR_IN_MSB = const(0x14) - MPL3115_P_ARLARM_MSB = const(0x16) - MPL3115_T_ARLARM = const(0x18) - MPL3115_P_ARLARM_WND_MSB = const(0x19) - MPL3115_T_ARLARM_WND = const(0x1b) - MPL3115_P_MIN_DATA = const(0x1c) - MPL3115_T_MIN_DATA = const(0x1f) - MPL3115_P_MAX_DATA = const(0x21) - MPL3115_T_MAX_DATA = const(0x24) - MPL3115_CTRL_REG1 = const(0x26) - MPL3115_CTRL_REG2 = const(0x27) - MPL3115_CTRL_REG3 = const(0x28) - MPL3115_CTRL_REG4 = const(0x29) - MPL3115_CTRL_REG5 = const(0x2a) - MPL3115_OFFSET_P = const(0x2b) - MPL3115_OFFSET_T = const(0x2c) - MPL3115_OFFSET_H = const(0x2d) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21', mode = PRESSURE): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.STA_reg = bytearray(1) - self.mode = mode - - if self.mode is PRESSURE: - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0x38])) # barometer mode, not raw, oversampling 128, minimum time 512 ms - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_PT_DATA_CFG, bytes([0x07])) # no events detected - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0x39])) # active - elif self.mode is ALTITUDE: - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0xB8])) # altitude mode, not raw, oversampling 128, minimum time 512 ms - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_PT_DATA_CFG, bytes([0x07])) # no events detected - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0xB9])) # active - else: - raise MPL3115A2exception("Invalid Mode MPL3115A2") - - if self._read_status(): - pass - else: - raise MPL3115A2exception("Error with MPL3115A2") - - def _read_status(self): - while True: - self.i2c.readfrom_mem_into(MPL3115_I2CADDR, MPL3115_STATUS, self.STA_reg) - - if(self.STA_reg[0] == 0): - time.sleep(0.01) - pass - elif(self.STA_reg[0] & 0x04) == 4: - return True - else: - return False - - def pressure(self): - if self.mode == ALTITUDE: - raise MPL3115A2exception("Incorrect Measurement Mode MPL3115A2") - - OUT_P_MSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_MSB,1) - OUT_P_CSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_CSB,1) - OUT_P_LSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_LSB,1) - - return float((OUT_P_MSB[0] << 10) + (OUT_P_CSB[0] << 2) + ((OUT_P_LSB[0] >> 6) & 0x03) + ((OUT_P_LSB[0] >> 4) & 0x03) / 4.0) - - def altitude(self): - if self.mode == PRESSURE: - raise MPL3115A2exception("Incorrect Measurement Mode MPL3115A2") - - OUT_P_MSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_MSB,1) - OUT_P_CSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_CSB,1) - OUT_P_LSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_LSB,1) - - alt_int = (OUT_P_MSB[0] << 8) + (OUT_P_CSB[0]) - alt_frac = ((OUT_P_LSB[0] >> 4) & 0x0F) - - if alt_int > 32767: - alt_int -= 65536 - - return float(alt_int + alt_frac / 16.0) - - def temperature(self): - OUT_T_MSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_TEMP_DATA_MSB,1) - OUT_T_LSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_TEMP_DATA_LSB,1) - - temp_int = OUT_T_MSB[0] - temp_frac = OUT_T_LSB[0] - - if temp_int > 127: - temp_int -= 256 - - return float(temp_int + temp_frac / 256.0) diff --git a/pysense/lib/SI7006A20.py b/pysense/lib/SI7006A20.py deleted file mode 100644 index d9a4025..0000000 --- a/pysense/lib/SI7006A20.py +++ /dev/null @@ -1,118 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C -import math - -__version__ = '0.0.2' - -class SI7006A20: - """ class for handling the temperature sensor SI7006-A20 - +/- 1 deg C error for temperature - +/- 5% error for relative humidity - datasheet available at https://www.silabs.com/documents/public/data-sheets/Si7006-A20.pdf """ - - SI7006A20_I2C_ADDR = const(0x40) - - TEMP_NOHOLDMASTER = const(0xF3) - HUMD_NOHOLDMASTER = const(0xF5) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - def _getWord(self, high, low): - return ((high & 0xFF) << 8) + (low & 0xFF) - - def temperature(self): - """ obtaining the temperature(degrees Celsius) measured by sensor """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xF3])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 3) - #print("CRC Raw temp data: " + hex(data[0]*65536 + data[1]*256 + data[2])) - data = self._getWord(data[0], data[1]) - temp = ((175.72 * data) / 65536.0) - 46.85 - return temp - - def humidity(self): - """ obtaining the relative humidity(%) measured by sensor """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xF5])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 2) - data = self._getWord(data[0], data[1]) - humidity = ((125.0 * data) / 65536.0) - 6.0 - return humidity - - def read_user_reg(self): - """ reading the user configuration register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xE7])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return data[0] - - def read_heater_reg(self): - """ reading the heater configuration register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0x11])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return data[0] - - def read_electronic_id(self): - """ reading electronic identifier """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xFA]) + bytearray([0x0F])) - time.sleep(0.5) - sna = self.i2c.readfrom(SI7006A20_I2C_ADDR, 4) - time.sleep(0.1) - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xFC]) + bytearray([0xC9])) - time.sleep(0.5) - snb = self.i2c.readfrom(SI7006A20_I2C_ADDR, 4) - return [sna[0], sna[1], sna[2], sna[3], snb[0], snb[1], snb[2], snb[3]] - - def read_firmware(self): - """ reading firmware version """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0x84])+ bytearray([0xB8])) - time.sleep(0.5) - fw = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return fw[0] - - def read_reg(self, reg_addr): - """ reading a register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([reg_addr])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return data[0] - - def write_reg(self, reg_addr, value): - """ writing a register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([reg_addr])+bytearray([value])) - time.sleep(0.1) - - def dew_point(self): - """ computing the dew pointe temperature (deg C) for the current Temperature and Humidity measured pair - at dew-point temperature the relative humidity is 100% """ - temp = self.temperature() - humid = self.humidity() - h = (math.log(humid, 10) - 2) / 0.4343 + (17.62 * temp) / (243.12 + temp) - dew_p = 243.12 * h / (17.62 - h) - return dew_p - - def humid_ambient(self, t_ambient, dew_p = None): - """ returns the relative humidity compensated for the current Ambient temperature - for ex: T-Ambient is 24.4 degC, but sensor indicates Temperature = 31.65 degC and Humidity = 47.3% - -> then the actual Relative Humidity is 72.2% - this is computed because the dew-point should be the same """ - if dew_p is None: - dew_p = self.dew_point() - h = 17.62 * dew_p / (243.12 + dew_p) - h_ambient = math.pow(10, (h - (17.62 * t_ambient) / (243.12 + t_ambient)) * 0.4343 + 2) - return h_ambient diff --git a/pysense/lib/pysense.py b/pysense/lib/pysense.py deleted file mode 100644 index 964ae24..0000000 --- a/pysense/lib/pysense.py +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -# See https://docs.pycom.io for more information regarding library specifics - -from pycoproc import Pycoproc - -__version__ = '1.4.1' - -class Pysense(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, Pycoproc.PYSENSE, i2c, sda, scl) diff --git a/pysense/main.py b/shields/pysense_1.py similarity index 100% rename from pysense/main.py rename to shields/pysense_1.py From eb3f45b0452dbe1f6f56256e874339e14c480e3c Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:29:28 +0100 Subject: [PATCH 17/39] fix pysense --- shields/pysense_1.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/shields/pysense_1.py b/shields/pysense_1.py index 695aa79..0a0d4b1 100644 --- a/shields/pysense_1.py +++ b/shields/pysense_1.py @@ -12,7 +12,7 @@ import time import pycom -from pysense import Pysense +from pycoproc_1 import Pycoproc import machine from LIS2HH12 import LIS2HH12 @@ -23,7 +23,7 @@ pycom.heartbeat(False) pycom.rgbled(0x0A0A08) # white -py = Pysense() +py = Pycoproc(Pycoproc.PYSENSE) mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals print("MPL3115A2 temperature: " + str(mp.temperature())) From 755786daa6d4e7062d880cf14f7da42d97ed711d Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:31:41 +0100 Subject: [PATCH 18/39] mv pytrack1 --- pytrack/lib/L76GNSS.py | 119 ---------------- pytrack/lib/LIS2HH12.py | 178 ------------------------ pytrack/lib/pytrack.py | 18 --- pytrack/main.py => shields/pytrack_1.py | 0 4 files changed, 315 deletions(-) delete mode 100644 pytrack/lib/L76GNSS.py delete mode 100644 pytrack/lib/LIS2HH12.py delete mode 100644 pytrack/lib/pytrack.py rename pytrack/main.py => shields/pytrack_1.py (100%) diff --git a/pytrack/lib/L76GNSS.py b/pytrack/lib/L76GNSS.py deleted file mode 100644 index 37cc2fd..0000000 --- a/pytrack/lib/L76GNSS.py +++ /dev/null @@ -1,119 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from machine import Timer -import time -import gc -import binascii - - -class L76GNSS: - - GPS_I2CADDR = const(0x10) - - def __init__(self, pytrack=None, sda='P22', scl='P21', timeout=None, buffer=64): - if pytrack is not None: - self.i2c = pytrack.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.chrono = Timer.Chrono() - - self.timeout = timeout - self.timeout_status = True - self.buffer = buffer - - self.reg = bytearray(1) - self.i2c.writeto(GPS_I2CADDR, self.reg) - - def _read(self): - self.reg = self.i2c.readfrom(GPS_I2CADDR, self.buffer) - return self.reg - - def _convert_coords(self, gngll_s): - lat = gngll_s[1] - lat_d = (float(lat) // 100) + ((float(lat) % 100) / 60) - lon = gngll_s[3] - lon_d = (float(lon) // 100) + ((float(lon) % 100) / 60) - if gngll_s[2] == 'S': - lat_d *= -1 - if gngll_s[4] == 'W': - lon_d *= -1 - return(lat_d, lon_d) - - def coordinates(self, debug=False): - lat_d, lon_d, debug_timeout = None, None, False - if self.timeout is not None: - self.chrono.reset() - self.chrono.start() - nmea = b'' - while True: - if self.timeout is not None and self.chrono.read() >= self.timeout: - self.chrono.stop() - chrono_timeout = self.chrono.read() - self.chrono.reset() - self.timeout_status = False - debug_timeout = True - if not self.timeout_status: - gc.collect() - break - nmea += self._read().lstrip(b'\n\n').rstrip(b'\n\n') - gngll_idx = nmea.find(b'GNGLL') - gpgll_idx = nmea.find(b'GPGLL') - if gngll_idx < 0 and gpgll_idx >= 0: - gngll_idx = gpgll_idx - if gngll_idx >= 0: - gngll = nmea[gngll_idx:] - e_idx = gngll.find(b'\r\n') - if e_idx >= 0: - try: - gngll = gngll[:e_idx].decode('ascii') - gngll_s = gngll.split(',') - lat_d, lon_d = self._convert_coords(gngll_s) - except Exception: - pass - finally: - nmea = nmea[(gngll_idx + e_idx):] - gc.collect() - break - else: - gc.collect() - if len(nmea) > 410: # i suppose it can be safely changed to 82, which is longest NMEA frame - nmea = nmea[-5:] # $GNGL without last L - time.sleep(0.1) - self.timeout_status = True - if debug and debug_timeout: - print('GPS timed out after %f seconds' % (chrono_timeout)) - return(None, None) - else: - return(lat_d, lon_d) - - def dump_nmea(self): - nmea = b'' - while True: - nmea = self._read().lstrip(b'\n\n').rstrip(b'\n\n') - start_idx = nmea.find(b'$') - #print('raw[{}]: {}'.format(start_idx, nmea)) - if nmea is not None and len(nmea) > 0: - if start_idx != 0: - if len(nmea[:start_idx]) > 1: - print('{}'.format(nmea[:start_idx].decode('ASCII')), end='') - if len(nmea[start_idx:]) > 1: - print('{}'.format(nmea[start_idx:].decode('ASCII')), end='') - - def _checksum(self, nmeadata): - calc_cksum = 0 - for s in nmeadata: - calc_cksum ^= ord(s) - return('{:X}'.format(calc_cksum)) - - def write(self, data): - self.i2c.writeto(GPS_I2CADDR, '${}*{}\r\n'.format(data, self._checksum(data)) ) diff --git a/pytrack/lib/LIS2HH12.py b/pytrack/lib/LIS2HH12.py deleted file mode 100644 index af2812d..0000000 --- a/pytrack/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (thresold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (thresold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used thresold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pytrack/lib/pytrack.py b/pytrack/lib/pytrack.py deleted file mode 100644 index 07d600d..0000000 --- a/pytrack/lib/pytrack.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from pycoproc import Pycoproc - -__version__ = '1.4.1' - -class Pytrack(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, Pycoproc.PYTRACK, i2c, sda, scl) diff --git a/pytrack/main.py b/shields/pytrack_1.py similarity index 100% rename from pytrack/main.py rename to shields/pytrack_1.py From 1995d86bf1759cc8b79eae522b65d8156650f9fc Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:33:08 +0100 Subject: [PATCH 19/39] fix pytrack --- shields/pytrack_1.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/shields/pytrack_1.py b/shields/pytrack_1.py index ddb44af..4751617 100644 --- a/shields/pytrack_1.py +++ b/shields/pytrack_1.py @@ -18,7 +18,7 @@ from machine import RTC from machine import SD from L76GNSS import L76GNSS -from pytrack import Pytrack +from pycoproc_1 import Pycoproc time.sleep(2) gc.enable() @@ -31,7 +31,7 @@ utime.timezone(7200) print('Adjusted from UTC to EST timezone', utime.localtime(), '\n') -py = Pytrack() +py = Pycoproc(Pycoproc.PYTRACK) l76 = L76GNSS(py, timeout=30) # sd = SD() From 6f8ddd5c1f524457faf53cac00237d7a320b3145 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 12:38:54 +0100 Subject: [PATCH 20/39] mv pybytes --- pybytes/pyscan/lib/LIS2HH12.py | 178 ----- pybytes/pyscan/lib/LTR329ALS01.py | 80 -- pybytes/pyscan/lib/MFRC630.mpy | Bin 15421 -> 0 bytes pybytes/pyscan/lib/MFRC630.py | 756 ------------------ pybytes/pyscan/lib/pycoproc.py | 294 ------- pybytes/pyscan/lib/pyscan.py | 18 - pybytes/pysense/lib/LIS2HH12.py | 178 ----- pybytes/pysense/lib/LTR329ALS01.py | 80 -- pybytes/pysense/lib/MPL3115A2.py | 129 --- pybytes/pysense/lib/SI7006A20.py | 118 --- pybytes/pysense/lib/pycoproc.py | 294 ------- pybytes/pysense/lib/pysense.py | 18 - pybytes/pytrack/lib/L76GNSS.py | 96 --- pybytes/pytrack/lib/LIS2HH12.py | 178 ----- pybytes/pytrack/lib/pycoproc.py | 294 ------- pybytes/pytrack/lib/pytrack.py | 18 - {pybytes => shields}/README.md | 0 .../main.py => shields/pyscan_1_pybytes.py | 0 .../main.py => shields/pysense_1_pybytes.py | 0 .../main.py => shields/pytrack_1_pybytes.py | 0 20 files changed, 2729 deletions(-) delete mode 100644 pybytes/pyscan/lib/LIS2HH12.py delete mode 100644 pybytes/pyscan/lib/LTR329ALS01.py delete mode 100644 pybytes/pyscan/lib/MFRC630.mpy delete mode 100644 pybytes/pyscan/lib/MFRC630.py delete mode 100644 pybytes/pyscan/lib/pycoproc.py delete mode 100644 pybytes/pyscan/lib/pyscan.py delete mode 100644 pybytes/pysense/lib/LIS2HH12.py delete mode 100644 pybytes/pysense/lib/LTR329ALS01.py delete mode 100644 pybytes/pysense/lib/MPL3115A2.py delete mode 100644 pybytes/pysense/lib/SI7006A20.py delete mode 100644 pybytes/pysense/lib/pycoproc.py delete mode 100644 pybytes/pysense/lib/pysense.py delete mode 100644 pybytes/pytrack/lib/L76GNSS.py delete mode 100644 pybytes/pytrack/lib/LIS2HH12.py delete mode 100644 pybytes/pytrack/lib/pycoproc.py delete mode 100644 pybytes/pytrack/lib/pytrack.py rename {pybytes => shields}/README.md (100%) rename pybytes/pyscan/main.py => shields/pyscan_1_pybytes.py (100%) rename pybytes/pysense/main.py => shields/pysense_1_pybytes.py (100%) rename pybytes/pytrack/main.py => shields/pytrack_1_pybytes.py (100%) diff --git a/pybytes/pyscan/lib/LIS2HH12.py b/pybytes/pyscan/lib/LIS2HH12.py deleted file mode 100644 index 49a6b5a..0000000 --- a/pybytes/pyscan/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (thresold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (thresold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used thresold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pybytes/pyscan/lib/LTR329ALS01.py b/pybytes/pyscan/lib/LTR329ALS01.py deleted file mode 100644 index 49e3439..0000000 --- a/pybytes/pyscan/lib/LTR329ALS01.py +++ /dev/null @@ -1,80 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C - -class LTR329ALS01: - ALS_I2CADDR = const(0x29) # The device's I2C address - - ALS_CONTR_REG = const(0x80) - ALS_MEAS_RATE_REG = const(0x85) - - ALS_DATA_CH1_LOW = const(0x88) - ALS_DATA_CH1_HIGH = const(0x89) - ALS_DATA_CH0_LOW = const(0x8A) - ALS_DATA_CH0_HIGH = const(0x8B) - - ALS_GAIN_1X = const(0x00) - ALS_GAIN_2X = const(0x01) - ALS_GAIN_4X = const(0x02) - ALS_GAIN_8X = const(0x03) - ALS_GAIN_48X = const(0x06) - ALS_GAIN_96X = const(0x07) - - ALS_INT_50 = const(0x01) - ALS_INT_100 = const(0x00) - ALS_INT_150 = const(0x04) - ALS_INT_200 = const(0x02) - ALS_INT_250 = const(0x05) - ALS_INT_300 = const(0x06) - ALS_INT_350 = const(0x07) - ALS_INT_400 = const(0x03) - - ALS_RATE_50 = const(0x00) - ALS_RATE_100 = const(0x01) - ALS_RATE_200 = const(0x02) - ALS_RATE_500 = const(0x03) - ALS_RATE_1000 = const(0x04) - ALS_RATE_2000 = const(0x05) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21', gain = ALS_GAIN_1X, integration = ALS_INT_100, rate = ALS_RATE_500): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - contr = self._getContr(gain) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_CONTR_REG, bytearray([contr])) - - measrate = self._getMeasRate(integration, rate) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_MEAS_RATE_REG, bytearray([measrate])) - - time.sleep(0.01) - - def _getContr(self, gain): - return ((gain & 0x07) << 2) + 0x01 - - def _getMeasRate(self, integration, rate): - return ((integration & 0x07) << 3) + (rate & 0x07) - - def _getWord(self, high, low): - return ((high & 0xFF) << 8) + (low & 0xFF) - - def light(self): - ch1low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_LOW, 1) - ch1high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_HIGH, 1) - data1 = int(self._getWord(ch1high[0], ch1low[0])) - - ch0low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_LOW, 1) - ch0high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_HIGH, 1) - data0 = int(self._getWord(ch0high[0], ch0low[0])) - - return (data0, data1) diff --git a/pybytes/pyscan/lib/MFRC630.mpy b/pybytes/pyscan/lib/MFRC630.mpy deleted file mode 100644 index 81ee92f4c847e5b10adb5872cc68380450f864f7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 15421 zcmcIL3sf7|mGk)d1GWLnfaMPZejo^hNEnRkII)E!u!2A!1SVm-BY^}c5r{}4#@lv1 z!p0_c(m3uXY1*_-He0v(f-&GU|JrfeO}ptiyGiPV+Aur#vg)3U&vg|59-&{VOT;DVQt#E=l;4_>`75U~6e9s z-@?n#ckpr~;!G67S!h3AfyVJlbP%tCvDxSV&Oyg{`>DaA?ji~kLhAg@qjLtt*btExGfhK z1AgVPdk+HsD8r8v{ElN|fZr6yPcZyJ2~Wmjz^~H9x+#Y-MsX<4p#*&wmm;0$!UmvS zjmzM=2A9J%A72A-53Yc#7gr*k5nl^n9#?@O*MZSSFxmu0SA)@;!RQ(=x)zMy0!G(? z(Obdj&jIZ=F#38hdOH|>0~mcHIClp+ig%)Wu^Ao1_2?_ug1(Ba=xf-9?!yh}e%y$@ zfp?(?upNC9-vkrUgdW5W^ljV>6Vd`sccO=ID|#5Wp?| zZuEWJg&xH>qsQ5G8kHEDN-vQTscn^4J6fE5fKIQP=0cjNX381|bXb%J35%}B%pSuC~WlDJuV2%RCy(lN| zYbftNl#|_>Uf|_$6X!wrVdP1{k04JfK7l-G_)+9Z$B!XT27VlQmf$ClXDNOXd6wa) zkY_obM4n7MjXYWS6!NUV4z3 z^5o&?ktZL&fIJ2GMdVqFUqT)|K8HN(@XwKFJ$?;&HsIHhXCt0RoZq@)Y5V zD5qP=UaF+GR1k)|gML9+E(lUe6a$X3~^HHx*n zoh};~o4}a}bG5iM4BDLyZkMgy=3cAFYj>O79qj`7vQfXTONw!K?Ka!pMaglpx7_xY z#^j@2baZjj(S)zi;B*OAv)jBeDTy>izqT5=t zRZWMJ%dMwcwzzH)h|ooeh;o-DBAQ*6h^VCyRcUofC&%pW zXf-p2@iFFh!C~vPIRw+Cka0bejNHspNOOZgQm6pQMldIZ*0baWv?NuNEW~oF45R6B zrQ%b<)Y8PpK{6D;$*>&b;|Oe*v)yfRyBsXh5@3V90g_~k+vRkylt|#aA)C3V-5M|< zci37Q-Mg4d3Kx=n*p@l1v${GV@LT^5(6 zm6jTs_=S*mSzxd>in_?^Yw2j#&Se*9vfFNT?_xy-St{T>S_Yj-&vR*hd=mQIZ` zU0voDvzDTvL&K@v=CYd|?X5PORpTT_gHv$3?9I&@D_R{6f#|1k0|8p?oz4!omID;Y zLR+(4>wHo=1JvBLkk$^gY_lQ0r?hs+>FphkcnQfcZ8An<($7BcM!hp-={G0D9_zc(xd z!nYe2f=pQoe}Y#(n3zta+Zh&sqtF`~iiShM0%c4b6ZR9W^A{rS@CHZxs}(r0RS5cr z`lACY6<8$djgCZCD3AVdI26_?Ps|^;`S)sU_Krjc)+kg^jM7Qz35I%aTcPAFlY8 zl^mDBrLSxv{pOz-nyTtbpyxc5bMf`MOmS-C18B1J0aRNeih18ct!UtzDDW+Gu6kC? zdl1cT{5Hz_4mvsAn&LY^>1HNNkE6-Lhfp6^4ZUe4xK(YM)IfDF{Xhq1$)LA)ATZ=l zh5Iz<+4wV>&E%+@HXIm=5TXphYOC*PWHzwa;kYy~w=ZLOZ=}~dlp67QQzN~>C1k!s zBhhraii*-WE(IFt42wZcNvVU8{=y}c z;j%{v!?!5E2Ta2K|EyUs%i6Eay0A`Y$^{ z_`aj?{XX#B5a3SgV*AdwAs^~X1&x^}SRzP}kx3EJ5D}5yvp4FGs05|?yiqS+CP{mg zNP90)nkAa$E_9>pC57P=gyDb749AXAhRi4N zC0g{DrnrSu_clXy23#!@s(lghS{ zOlI7#32Kn6yr{7$;n9@n=yu8E71KnsKN$>$GHUkYl5Vn!PclsvH4jlW7umy9IxYw% zrePALw4&q?@2X7x9EjgU&Jy~YBwNod;uYcJb_twrr&$8_5AD%pRlw0*j z^oQg6Bk14wJkO>I^oL=6Y*+UC^6fV|<(uy-$kTnEO+{;_GG6a5-Q2r5{lb>lZ5O`& z{(UN+F77G4uc6~&Y3Cl(SqYo|TkNj+HV z0!D>PrA^~$!bndUoj~`DPrWmLQoGRO6_;F#shBSs`ss93IxWRalBDI&5J?-ZlSLh+ zq9)z~VI*bVOCDikq_SBl6qhYkdzTb_Rmwa|lqph_Ii^+SD{5sHt1$n1U6i?ej_6V< z&*cG_OI9@nMwrQ#A7)!7deNVyE6bU-#y|$wIp8 zOOKh9DnAuS#O}$$IT(L#cIe_|e?akL%LJxmqM1{qbbs zW9W1r`r+yB+Coj~w)m-!I=hq1@a>&L@d64$I`A zOh}iB_`}JN25M6Ah2_MgyUt zNLITamfBE1Pnubg0&`!~ALjRX15pBlz7r4q!9D(Pq@X3lySgfQC25cwBgr0-EVH}K zER$_3lZ(OE$WokUEu594g)>?BI-EHBQfMcKnW^fVse(<@(P8C+rVl0=Lr=M>;E>qX z<%k@0b*~fAbJrGca+H+byt{T&7cBP;|3w-|8~VAA>KvkYW=AHs;X&@C51p~rW{A}` z*fz}5(CJt!=KTT{KFN79rgEmcQi|%Kxq=FR!@-J@5lg02u-bZQ{iSaBcTSSvL-Vi< zcjR;VX(u=Qjw^f%O~Jsv6j+|!*4ou#b$&X~f+{Bogv!n7PHLXY7ipvfSVmey-f-Bv zHx;_hh)=sU6c|b$86NhBH4p0fPK9ZvgX8a#4){ldfxf+nC%DuU+LL20jI1KRS?~j1 zNU$Js8z0d*XlE7X*~jx%=taR@BvPQ<@p}T%0iMxBN;0@Ka(Y<_oyo61PtvSq757r! zc~p3WgA(xb)wRFgm(#s$d%u6kKRO&%zX6-^g>A;_(Jy64Qw)coYc$MW{41Fq*^22N z5i6Z1;qi){><>M#KQxtA6c-x|#ia)L2e8uXoQ6hR8srCe;)=nYW%hw^@utSIrhY?N z*>%O(-cVM0IICoYH{qs=pr^ban;OdTPsnRGAx8cJ_Kb|4g~p+#2-(`K7uYQygPcfRxeJ&W*3ZEXyjOf4-ugUW=Y{V-?>ql09kKKU zqW=r?#o1H(?CIFs``?+Lc(+KOJ@MXKvGc__b8z>rsYstgAaDM%#xN6`mp0>Nv?iuJ zmdm%`#KXW1CV_%8LGJOHw_gRL$QOlWJ@T|r*axP~A8vVVUo}JvFk2mGCe>O1)6Kj9o|OC# zHkF`f$s@m#XIu6cw+T6N~0zMZcIEgU|k=Uliw2 zdHMQ0Vv~N2KJT~iqX~r-$gW9@R-HIZqZLBc0IX*B8-UsD0Rym`9XIInW)B(;LHH#e zs5BuhLO`pcmGP>M`A`#b#{C~|`Hy|%{3pVmCy{6g4t%)fSNp1`_rDXH?*@8!yyXj$ zH#X2DMN-HVnNP8sHH#8|H&gA9>P>G!rNwH=t1DAK!@^OmUVI;CCEF!xW%bBp6%(`V zD(hr5--UWCQs|PxLtVC-7PwlCH8QNy###VSYjL&r$-Hs3JQky8yjA@<<|S5Ot4FgD zs%rLfc;Zg-xg4Duzu5id>LH`~8 zASuNoMHUD7uH@l$jvyZlg@&ca+j>Z$9t;ijNAlbKQOYhn%6o%>{vqg@(6Q?k7tz50 z8kL$j^e(bG-qqnly}cu0zppB?$^v2n5jZaL-Y7Zpt!x?!?HS_h1JMZOSqK&gq;CT! zQ_ztIEFaee&Jl%i4m~4L!1M6aLBK~<7!F0MB3m0nQJ(zR%|jDt7+#r)D^&?SAITJA zEmcE+F_Jx_k-9y8zF!_(3CB<$;m#-{m3(vnlpgfMITjod*e2;` zf%PB5vGAc+die4HITS+s{8rL6+|@&x=AWu7p4cyZ3EsMa*C(pkp+xSA(~h6i`hI_( z^evTOk0AJM=iKb^^WBMW2&pO`mXt1$lt05t=F0XCmVA}pNRnrBr7n zy?7KMTBpg4%hO*`wV4H`yGbhE` zO``Ga)TyGQAHpjy(|LbHaR1&1XKI(j!=K~_>D=-LoLi=)zL4hKER_aanh`Q ready) - MFRC630_ISO14443_CMD_WUPA = const(0x52) # wake up type a (idle / halt -> ready) - MFRC630_ISO14443_CAS_LEVEL_1 = const(0x93) # Cascade level 1 for select. - MFRC630_ISO14443_CAS_LEVEL_2 = const(0x95) # Cascade level 2 for select. - MFRC630_ISO14443_CAS_LEVEL_3 = const(0x97) # Cascade level 3 for select. - MFRC630_MF_AUTH_KEY_A = const(0x60) # A key_type for mifare auth. - MFRC630_MF_AUTH_KEY_B = const(0x61) # A key_type for mifare auth. - MFRC630_MF_CMD_READ = const(0x30) # To read a block from mifare card. - MFRC630_MF_CMD_WRITE = const(0xA0) # To write a block to a mifare card. - MFRC630_MF_ACK = const(0x0A) # Sent by cards to acknowledge an operation. - - # registers - MFRC630_REG_COMMAND = const(0x00) # Starts and stops command execution - MFRC630_REG_HOSTCTRL = const(0x01) # Host control register - MFRC630_REG_FIFOCONTROL = const(0x02) # Control register of the FIFO - MFRC630_REG_WATERLEVEL = const(0x03) # Level of the FIFO underflow and overflow warning - MFRC630_REG_FIFOLENGTH = const(0x04) # Length of the FIFO - MFRC630_REG_FIFODATA = const(0x05) # Data In/Out exchange register of FIFO buffer - MFRC630_REG_IRQ0 = const(0x06) # Interrupt register 0 - MFRC630_REG_IRQ1 = const(0x07) # Interrupt register 1 - MFRC630_REG_IRQ0EN = const(0x08) # Interrupt enable register 0 - MFRC630_REG_IRQ1EN = const(0x09) # Interrupt enable register 1 - MFRC630_REG_ERROR = const(0x0A) # Error bits showing the error status of the last command execution - MFRC630_REG_STATUS = const(0x0B) # Contains status of the communication - MFRC630_REG_RXBITCTRL = const(0x0C) # Control for anticoll. adjustments for bit oriented protocols - MFRC630_REG_RXCOLL = const(0x0D) # Collision position register - MFRC630_REG_TCONTROL = const(0x0E) # Control of Timer 0..3 - MFRC630_REG_T0CONTROL = const(0x0F) # Control of Timer0 - MFRC630_REG_T0RELOADHI = const(0x10) # High register of the reload value of Timer0 - MFRC630_REG_T0RELOADLO = const(0x11) # Low register of the reload value of Timer0 - MFRC630_REG_T0COUNTERVALHI = const(0x12) # Counter value high register of Timer0 - MFRC630_REG_T0COUNTERVALLO = const(0x13) # Counter value low register of Timer0 - MFRC630_REG_T1CONTROL = const(0x14) # Control of Timer1 - MFRC630_REG_T1RELOADHI = const(0x15) # High register of the reload value of Timer1 - MFRC630_REG_T1COUNTERVALHI = const(0x17) # Counter value high register of Timer1 - MFRC630_REG_T1COUNTERVALLO = const(0x18) # Counter value low register of Timer1 - MFRC630_REG_T2CONTROL = const(0x19) # Control of Timer2 - MFRC630_REG_T2RELOADHI = const(0x1A) # High byte of the reload value of Timer2 - MFRC630_REG_T2RELOADLO = const(0x1B) # Low byte of the reload value of Timer2 - MFRC630_REG_T2COUNTERVALHI = const(0x1C) # Counter value high byte of Timer2 - MFRC630_REG_T2COUNTERVALLO = const(0x1D) # Counter value low byte of Timer2 - MFRC630_REG_T3CONTROL = const(0x1E) # Control of Timer3 - MFRC630_REG_T3RELOADHI = const(0x1F) # High byte of the reload value of Timer3 - MFRC630_REG_T3RELOADLO = const(0x20) # Low byte of the reload value of Timer3 - MFRC630_REG_T3COUNTERVALHI = const(0x21) # Counter value high byte of Timer3 - MFRC630_REG_T3COUNTERVALLO = const(0x22) # Counter value low byte of Timer3 - MFRC630_REG_T4CONTROL = const(0x23) # Control of Timer4 - MFRC630_REG_T4RELOADHI = const(0x24) # High byte of the reload value of Timer4 - MFRC630_REG_T4RELOADLO = const(0x25) # Low byte of the reload value of Timer4 - MFRC630_REG_T4COUNTERVALHI = const(0x26) # Counter value high byte of Timer4 - MFRC630_REG_T4COUNTERVALLO = const(0x27) # Counter value low byte of Timer4 - MFRC630_REG_DRVMOD = const(0x28) # Driver mode register - MFRC630_REG_TXAMP = const(0x29) # Transmitter amplifier register - MFRC630_REG_DRVCON = const(0x2A) # Driver configuration register - MFRC630_REG_TXL = const(0x2B) # Transmitter register - MFRC630_REG_TXCRCPRESET = const(0x2C) # Transmitter CRC control register, preset value - MFRC630_REG_RXCRCCON = const(0x2D) # Receiver CRC control register, preset value - MFRC630_REG_TXDATANUM = const(0x2E) # Transmitter data number register - MFRC630_REG_TXMODWIDTH = const(0x2F) # Transmitter modulation width register - MFRC630_REG_TXSYM10BURSTLEN = const(0x30) # Transmitter symbol 1 + symbol 0 burst length register - MFRC630_REG_TXWAITCTRL = const(0x31) # Transmitter wait control - MFRC630_REG_TXWAITLO = const(0x32) # Transmitter wait low - MFRC630_REG_FRAMECON = const(0x33) # Transmitter frame control - MFRC630_REG_RXSOFD = const(0x34) # Receiver start of frame detection - MFRC630_REG_RXCTRL = const(0x35) # Receiver control register - MFRC630_REG_RXWAIT = const(0x36) # Receiver wait register - MFRC630_REG_RXTHRESHOLD = const(0x37) # Receiver threshold register - MFRC630_REG_RCV = const(0x38) # Receiver register - MFRC630_REG_RXANA = const(0x39) # Receiver analog register - MFRC630_REG_RFU = const(0x3A) # (Reserved for future use) - MFRC630_REG_SERIALSPEED = const(0x3B) # Serial speed register - MFRC630_REG_LFO_TRIMM = const(0x3C) # Low-power oscillator trimming register - MFRC630_REG_PLL_CTRL = const(0x3D) # IntegerN PLL control register, for mcu clock output adjustment - MFRC630_REG_PLL_DIVOUT = const(0x3E) # IntegerN PLL control register, for mcu clock output adjustment - MFRC630_REG_LPCD_QMIN = const(0x3F) # Low-power card detection Q channel minimum threshold - MFRC630_REG_LPCD_QMAX = const(0x40) # Low-power card detection Q channel maximum threshold - MFRC630_REG_LPCD_IMIN = const(0x41) # Low-power card detection I channel minimum threshold - MFRC630_REG_LPCD_I_RESULT = const(0x42) # Low-power card detection I channel result register - MFRC630_REG_LPCD_Q_RESULT = const(0x43) # Low-power card detection Q channel result register - MFRC630_REG_PADEN = const(0x44) # PIN enable register - MFRC630_REG_PADOUT = const(0x45) # PIN out register - MFRC630_REG_PADIN = const(0x46) # PIN in register - MFRC630_REG_SIGOUT = const(0x47) # Enables and controls the SIGOUT Pin - MFRC630_REG_VERSION = const(0x7F) # Version and subversion register - - MFRC630_TXDATANUM_DATAEN = const(1 << 3) - MFRC630_RECOM_14443A_CRC = const(0x18) - - MFRC630_ERROR_EE_ERR = const(1 << 7) - MFRC630_ERROR_FIFOWRERR = const(1 << 6) - MFRC630_ERROR_FIFOOVL = const(1 << 5) - MFRC630_ERROR_MINFRAMEERR = const(1 << 4) - MFRC630_ERROR_NODATAERR = const(1 << 3) - MFRC630_ERROR_COLLDET = const(1 << 2) - MFRC630_ERROR_PROTERR = const(1 << 1) - MFRC630_ERROR_INTEGERR = const(1 << 0) - - MFRC630_CRC_ON = const(1) - MFRC630_CRC_OFF = const(0) - - MFRC630_IRQ0EN_IRQ_INV = const(1 << 7) - MFRC630_IRQ0EN_HIALERT_IRQEN = const(1 << 6) - MFRC630_IRQ0EN_LOALERT_IRQEN = const(1 << 5) - MFRC630_IRQ0EN_IDLE_IRQEN = const(1 << 4) - MFRC630_IRQ0EN_TX_IRQEN = const(1 << 3) - MFRC630_IRQ0EN_RX_IRQEN = const(1 << 2) - MFRC630_IRQ0EN_ERR_IRQEN = const(1 << 1) - MFRC630_IRQ0EN_RXSOF_IRQEN = const(1 << 0) - - MFRC630_IRQ1EN_TIMER0_IRQEN = const(1 << 0) - - MFRC630_TCONTROL_CLK_211KHZ = const(0b01) - MFRC630_TCONTROL_START_TX_END = const(0b01 << 4) - - MFRC630_IRQ1_GLOBAL_IRQ = const(1 << 6) - - MFRC630_IRQ0_ERR_IRQ = const(1 << 1) - MFRC630_IRQ0_RX_IRQ = const(1 << 2) - - def __init__(self, pyscan=None, sda='P22', scl='P21', timeout=None, debug=False): - if pyscan is not None: - self.i2c = pyscan.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - self._DEBUG = debug - self.mfrc630_cmd_reset() - - # ToDo: Timeout not yet implemented! - # self.chrono = Timer.Chrono() - # self.timeout = timeout - # self.timeout_status = True - - def print_debug(self, msg): - if self._DEBUG: - print(msg) - - def mfrc630_read_reg(self, reg): - return self.i2c.readfrom_mem(NFC_I2CADDR, reg, 1)[0] - - def mfrc630_write_reg(self, reg, data): - self.i2c.writeto_mem(NFC_I2CADDR, reg, bytes([data & 0xFF])) - - def mfrc630_write_regs(self, reg, data): - self.i2c.writeto_mem(NFC_I2CADDR, reg, bytes(data)) - - def mfrc630_read_fifo(self, len): - if len > 0: - return self.i2c.readfrom_mem(NFC_I2CADDR, MFRC630_REG_FIFODATA, len) - else: - return None - - def mfrc630_cmd_idle(self): - self.mfrc630_write_reg(MFRC630_REG_COMMAND, MFRC630_CMD_IDLE) - - def mfrc630_flush_fifo(self): - self.mfrc630_write_reg(MFRC630_REG_FIFOCONTROL, 1 << 4) - - def mfrc630_setup_fifo(self): - self.mfrc630_write_reg(MFRC630_REG_FIFOCONTROL, 0x90) - self.mfrc630_write_reg(MFRC630_REG_WATERLEVEL, 0xFE) - - def mfrc630_write_fifo(self, data): - self.mfrc630_write_regs(MFRC630_REG_FIFODATA, data) - - def mfrc630_cmd_load_protocol(self, rx, tx): - self.mfrc630_flush_fifo() - self.mfrc630_write_fifo([rx, tx]) - self.mfrc630_write_reg(MFRC630_REG_COMMAND, MFRC630_CMD_LOADPROTOCOL) - - def mfrc630_cmd_transceive(self, data): - self.mfrc630_cmd_idle() - self.mfrc630_flush_fifo() - self.mfrc630_setup_fifo() - self.mfrc630_write_fifo(data) - self.mfrc630_write_reg(MFRC630_REG_COMMAND, MFRC630_CMD_TRANSCEIVE) - - def mfrc630_cmd_init(self): - self.mfrc630_write_regs(MFRC630_REG_DRVMOD, self.MFRC630_RECOM_14443A_ID1_106) - self.mfrc630_write_reg(0x28, 0x8E) - self.mfrc630_write_reg(0x29, 0x15) - self.mfrc630_write_reg(0x2A, 0x11) - self.mfrc630_write_reg(0x2B, 0x06) - - def mfrc630_cmd_reset(self): - self.mfrc630_cmd_idle() - self.mfrc630_write_reg(MFRC630_REG_COMMAND, MFRC630_CMD_SOFTRESET) - - def mfrc630_clear_irq0(self): - self.mfrc630_write_reg(MFRC630_REG_IRQ0, ~(1 << 7)) - - def mfrc630_clear_irq1(self): - self.mfrc630_write_reg(MFRC630_REG_IRQ1, ~(1 << 7)) - - def mfrc630_irq0(self): - return self.mfrc630_read_reg(MFRC630_REG_IRQ0) - - def mfrc630_irq1(self): - return self.mfrc630_read_reg(MFRC630_REG_IRQ1) - - def mfrc630_timer_set_control(self, timer, value): - self.mfrc630_write_reg(MFRC630_REG_T0CONTROL + (5 * timer), value) - - def mfrc630_timer_set_reload(self, timer, value): - self.mfrc630_write_reg(MFRC630_REG_T0RELOADHI + (5 * timer), value >> 8) - self.mfrc630_write_reg(MFRC630_REG_T0RELOADLO + (5 * timer), 0xFF) - - def mfrc630_timer_set_value(self, timer, value): - self.mfrc630_write_reg(MFRC630_REG_T0COUNTERVALHI + (5 * timer), value >> 8) - self.mfrc630_write_reg(MFRC630_REG_T0COUNTERVALLO + (5 * timer), 0xFF) - - def mfrc630_fifo_length(self): - # should do 512 byte fifo handling here - return self.mfrc630_read_reg(MFRC630_REG_FIFOLENGTH) - - def mfrc630_status(self): - return self.mfrc630_read_reg(MFRC630_REG_STATUS) - - def mfrc630_error(self): - return self.mfrc630_read_reg(MFRC630_REG_ERROR) - - def mfrc630_cmd_load_key(self, key): - self.mfrc630_cmd_idle() - self.mfrc630_flush_fifo() - self.mfrc630_write_fifo(key) - self.mfrc630_write_reg(MFRC630_REG_COMMAND, MFRC630_CMD_LOADKEY) - - def mfrc630_cmd_auth(self, key_type, block_address, card_uid): - self.mfrc630_cmd_idle() - parameters = [ key_type, block_address, card_uid[0], card_uid[1], card_uid[2], card_uid[3] ] - self.mfrc630_flush_fifo() - self.mfrc630_write_fifo(parameters) - self.mfrc630_write_reg(MFRC630_REG_COMMAND, MFRC630_CMD_MFAUTHENT) - - def mfrc630_MF_read_block(self, block_address, dest): - self.mfrc630_flush_fifo() - - self.mfrc630_write_reg(MFRC630_REG_TXCRCPRESET, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_ON) - self.mfrc630_write_reg(MFRC630_REG_RXCRCCON, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_ON) - - send_req = [ MFRC630_MF_CMD_READ, block_address ] - - # configure a timeout timer. - timer_for_timeout = 0 # should match the enabled interupt. - - # enable the global IRQ for idle, errors and timer. - self.mfrc630_write_reg(MFRC630_REG_IRQ0EN, MFRC630_IRQ0EN_IDLE_IRQEN | MFRC630_IRQ0EN_ERR_IRQEN) - self.mfrc630_write_reg(MFRC630_REG_IRQ1EN, MFRC630_IRQ1EN_TIMER0_IRQEN) - - - # Set timer to 221 kHz clock, start at the end of Tx. - self.mfrc630_timer_set_control(timer_for_timeout, MFRC630_TCONTROL_CLK_211KHZ | MFRC630_TCONTROL_START_TX_END) - # Frame waiting time: FWT = (256 x 16/fc) x 2 FWI - # FWI defaults to four... so that would mean wait for a maximum of ~ 5ms - self.mfrc630_timer_set_reload(timer_for_timeout, 2000) # 2000 ticks of 5 usec is 10 ms. - self.mfrc630_timer_set_value(timer_for_timeout, 2000) - - irq1_value = 0 - irq0_value = 0 - - self.mfrc630_clear_irq0() # clear irq0 - self.mfrc630_clear_irq1() # clear irq1 - - # Go into send, then straight after in receive. - self.mfrc630_cmd_transceive(send_req) - - # block until we are done - while not (irq1_value & (1 << timer_for_timeout)): - irq1_value = self.mfrc630_irq1() - if (irq1_value & MFRC630_IRQ1_GLOBAL_IRQ): - self.print_debug("irq1: %x" % irq1_value) - break # stop polling irq1 and quit the timeout loop. - - self.mfrc630_cmd_idle() - - if irq1_value & (1 << timer_for_timeout): - self.print_debug("this indicates a timeout") - # this indicates a timeout - return 0 - - irq0_value = self.mfrc630_irq0() - if (irq0_value & MFRC630_IRQ0_ERR_IRQ): - self.print_debug("some error") - # some error - return 0 - - self.print_debug("all seems to be well...") - # all seems to be well... - buffer_length = self.mfrc630_fifo_length() - rx_len = buffer_length if (buffer_length <= 16) else 16 - dest = self.mfrc630_read_fifo(rx_len) - return rx_len - - - def mfrc630_iso14443a_WUPA_REQA(self, instruction): - self.mfrc630_cmd_idle() - - self.mfrc630_flush_fifo() - - #Set register such that we sent 7 bits, set DataEn such that we can send data - self.mfrc630_write_reg(MFRC630_REG_TXDATANUM, 7 | MFRC630_TXDATANUM_DATAEN) - - # disable the CRC registers - self.mfrc630_write_reg(MFRC630_REG_TXCRCPRESET, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_OFF) - self.mfrc630_write_reg(MFRC630_REG_RXCRCCON, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_OFF) - self.mfrc630_write_reg(MFRC630_REG_RXBITCTRL, 0) - - # clear interrupts - self.mfrc630_clear_irq0() - self.mfrc630_clear_irq1() - - # enable the global IRQ for Rx done and Errors. - self.mfrc630_write_reg(MFRC630_REG_IRQ0EN, MFRC630_IRQ0EN_RX_IRQEN | MFRC630_IRQ0EN_ERR_IRQEN) - self.mfrc630_write_reg(MFRC630_REG_IRQ1EN, MFRC630_IRQ1EN_TIMER0_IRQEN) - - # configure timer - timer_for_timeout = 0 - # Set timer to 221 kHz clock, start at the end of Tx. - self.mfrc630_timer_set_control(timer_for_timeout, MFRC630_TCONTROL_CLK_211KHZ | MFRC630_TCONTROL_START_TX_END) - - # Frame waiting time: FWT = (256 x 16/fc) x 2 FWI - # FWI defaults to four... so that would mean wait for a maximum of ~ 5ms - self.mfrc630_timer_set_reload(timer_for_timeout, 1000) # 1000 ticks of 5 usec is 5 ms. - self.mfrc630_timer_set_value(timer_for_timeout, 1000) - - # Go into send, then straight after in receive. - self.mfrc630_cmd_transceive([instruction]) - self.print_debug('Sending REQA') - - # block until we are done - irq1_value = 0 - while not (irq1_value & (1 << timer_for_timeout)): - irq1_value = self.mfrc630_irq1() - if irq1_value & MFRC630_IRQ1_GLOBAL_IRQ: # either ERR_IRQ or RX_IRQ - break # stop polling irq1 and quit the timeout loop - - self.print_debug('After waiting for answer') - self.mfrc630_cmd_idle() - - # if no Rx IRQ, or if there's an error somehow, return 0 - irq0 = self.mfrc630_irq0() - if (not (irq0 & MFRC630_IRQ0_RX_IRQ)) or (irq0 & MFRC630_IRQ0_ERR_IRQ): - self.print_debug('No RX, irq1: %x irq0: %x' % (irq1_value, irq0)) - return 0 - - return self.mfrc630_fifo_length() - self.print_debug("rx_len:", rx_len) - if rx_len == 2: # ATQA should answer with 2 bytes - res = self.mfrc630_read_fifo(rx_len) - self.print_debug('ATQA answer:', res) - return res - return 0 - - def mfrc630_print_block(self, data, len): - if self._DEBUG: - print(self.mfrc630_format_block(data, len)) - - def mfrc630_format_block(self, data, len): - if type(data) == bytearray: - len_i = 0 - try: - len_i = int(len) - except: - pass - if (len_i > 0): - return ' '.join('{:02x}'.format(x) for x in data[:len_i]).upper() - else: - return ' '.join('{:02x}'.format(x) for x in data).upper() - else: - self.print_debug("DATA has type: " + str(type(data))) - try: - return "Length: %d Data: %s" % (len,binascii.hexlify(data,' ')) - except: - return "Data: %s with Length: %s" % (str(data), len) - - - def mfrc630_iso14443a_select(self, uid): - - self.print_debug("Starting select") - - self.mfrc630_cmd_idle() - self.mfrc630_flush_fifo() - - # enable the global IRQ for Rx done and Errors. - self.mfrc630_write_reg(MFRC630_REG_IRQ0EN, MFRC630_IRQ0EN_RX_IRQEN | MFRC630_IRQ0EN_ERR_IRQEN) - self.mfrc630_write_reg(MFRC630_REG_IRQ1EN, MFRC630_IRQ1EN_TIMER0_IRQEN) # only trigger on timer for irq1 - - # configure a timeout timer, use timer 0. - timer_for_timeout = 0 - - # Set timer to 221 kHz clock, start at the end of Tx. - self.mfrc630_timer_set_control(timer_for_timeout, MFRC630_TCONTROL_CLK_211KHZ | MFRC630_TCONTROL_START_TX_END) - # Frame waiting time: FWT = (256 x 16/fc) x 2 FWI - # FWI defaults to four... so that would mean wait for a maximum of ~ 5ms - - self.mfrc630_timer_set_reload(timer_for_timeout, 1000) # 1000 ticks of 5 usec is 5 ms. - self.mfrc630_timer_set_value(timer_for_timeout, 1000) - - for cascade_level in range(1, 4): - self.print_debug("Starting cascade level: %d" % cascade_level) - cmd = 0 - known_bits = 0 # known bits of the UID at this level so far. - send_req = bytearray(7) # used as Tx buffer. - uid_this_level = send_req[2:] - message_length = 0 - if cascade_level == 1: - cmd = MFRC630_ISO14443_CAS_LEVEL_1; - elif cascade_level == 2: - cmd = MFRC630_ISO14443_CAS_LEVEL_2; - elif cascade_level == 3: - cmd = MFRC630_ISO14443_CAS_LEVEL_3; - - # disable CRC in anticipation of the anti collision protocol - self.mfrc630_write_reg(MFRC630_REG_TXCRCPRESET, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_OFF) - self.mfrc630_write_reg(MFRC630_REG_RXCRCCON, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_OFF) - - # max 32 loops of the collision loop. - for collision_n in range(0, 33): - self.print_debug("CL: %d, coll loop: %d, kb %d long" % (cascade_level, collision_n, known_bits)) - self.mfrc630_print_block(uid_this_level, (known_bits + 8 - 1) / 8) - # clear interrupts - self.mfrc630_clear_irq0() - self.mfrc630_clear_irq1() - - send_req[0] = cmd; - send_req[1] = 0x20 + known_bits - send_req[2:5] = uid_this_level[0:3] - - # Only transmit the last 'x' bits of the current byte we are discovering - # First limit the txdatanum, such that it limits the correct number of bits. - self.mfrc630_write_reg(MFRC630_REG_TXDATANUM, (known_bits % 8) | MFRC630_TXDATANUM_DATAEN) - - # ValuesAfterColl: If cleared, every received bit after a collision is - # replaced by a zero. This function is needed for ISO/IEC14443 anticollision (0<<7). - # We want to shift the bits with RxAlign - rxalign = known_bits % 8; - self.print_debug("Setting rx align to: %d" % rxalign) - self.mfrc630_write_reg(MFRC630_REG_RXBITCTRL, (0 << 7) | (rxalign << 4)) - - # then sent the send_req to the hardware, - # (known_bits / 8) + 1): The ceiled number of bytes by known bits. - # +2 for cmd and NVB. - if ((known_bits % 8) == 0): - message_length = ((known_bits / 8)) + 2; - else: - message_length = ((known_bits / 8) + 1) + 2; - - # Send message - self.mfrc630_cmd_transceive(send_req[:int(message_length)]) - - # block until we are done - irq1_value = 0 - while not (irq1_value & (1 << timer_for_timeout)): - irq1_value = self.mfrc630_irq1() - # either ERR_IRQ or RX_IRQ or Timer - if (irq1_value & MFRC630_IRQ1_GLOBAL_IRQ): - break # stop polling irq1 and quit the timeout loop. - - self.mfrc630_cmd_idle() - - # next up, we have to check what happened. - irq0 = self.mfrc630_irq0() - error = self.mfrc630_read_reg(MFRC630_REG_ERROR) - coll = self.mfrc630_read_reg(MFRC630_REG_RXCOLL) - self.print_debug("irq0: %x coll: %x error: %x " % (irq0, coll, error)) - collision_pos = 0 - if irq0 and MFRC630_IRQ0_ERR_IRQ: # some error occured. - self.print_debug("some error occured.") - # Check what kind of error. - if (error & MFRC630_ERROR_COLLDET): - # A collision was detected... - if (coll & (1 << 7)): - collision_pos = coll & (~(1 << 7)) - self.print_debug("Collision at %x", collision_pos) - # This be a true collision... we have to select either the address - # with 1 at this position or with zero - # ISO spec says typically a 1 is added, that would mean: - # uint8_t selection = 1; - - # However, it makes sense to allow some kind of user input for this, so we use the - # current value of uid at this position, first index right byte, then shift such - # that it is in the rightmost position, ten select the last bit only. - # We cannot compensate for the addition of the cascade tag, so this really - # only works for the first cascade level, since we only know whether we had - # a cascade level at the end when the SAK was received. - choice_pos = known_bits + collision_pos - selection = (uid[((choice_pos + (cascade_level - 1) * 3) / 8)] >> ((choice_pos) % 8)) & 1 - - # We just OR this into the UID at the right position, later we - # OR the UID up to this point into uid_this_level. - uid_this_level[((choice_pos) / 8)] |= selection << ((choice_pos) % 8) - known_bits = known_bits + 1 # add the bit we just decided. - self.print_debug("Known Bits: %d" % known_bits) - - self.print_debug("uid_this_level now kb %d long: " % known_bits) - self.mfrc630_print_block(uid_this_level, 10) - else: - # Datasheet of mfrc630: - # bit 7 (CollPosValid) not set: - # Otherwise no collision is detected or - # the position of the collision is out of the range of bits CollPos. - self.print_debug("Collision but no valid collpos.") - collision_pos = 0x20 - known_bits - else: - # we got data despite an error, and no collisions, that means we can still continue. - collision_pos = 0x20 - known_bits - self.print_debug("Got data despite error: %x, setting collision_pos to: %x" % (error, collision_pos)) - elif (irq0 & MFRC630_IRQ0_RX_IRQ): - # we got data, and no collisions, that means all is well. - self.print_debug("we got data, and no collisions, that means all is well.") - collision_pos = 0x20 - known_bits - self.print_debug("Got data, no collision, setting to: %x" % collision_pos) - else: - # We have no error, nor received an RX. No response, no card? - self.print_debug("We have no error, nor received an RX. No response, no card?") - return 0 - - self.print_debug("collision_pos: %x" % collision_pos) - # read the UID Cln so far from the buffer. - rx_len = self.mfrc630_fifo_length() - buf = self.mfrc630_read_fifo(rx_len if rx_len < 5 else 5) - - self.print_debug("Fifo %d long" % rx_len) - self.mfrc630_print_block(buf, rx_len) - - self.print_debug("uid_this_level kb %d long: " % known_bits) - self.mfrc630_print_block(uid_this_level, (known_bits + 8 - 1) / 8) - - # move the buffer into the uid at this level, but OR the result such that - # we do not lose the bit we just set if we have a collision. - for rbx in range(0, rx_len): - uid_this_level[int(known_bits / 8) + rbx] = uid_this_level[int(known_bits / 8) + rbx] | buf[rbx] - self.print_debug("uid_this_level after reading buffer (known_bits=%d):" % known_bits) - self.mfrc630_print_block(uid_this_level, 0) - self.print_debug("known_bits: %x + collision_pos: %x = %x" % (known_bits, collision_pos, known_bits + collision_pos)) - known_bits = known_bits + collision_pos - self.print_debug("known_bits: %x" % known_bits) - - if known_bits >= 32: - self.print_debug("exit collision loop: uid_this_level kb %d long: " % known_bits); - self.mfrc630_print_block(uid_this_level, 10) - break; # done with collision loop - # end collission loop - - # check if the BCC matches - bcc_val = uid_this_level[4] # always at position 4, either with CT UID[0-2] or UID[0-3] in front. - bcc_calc = uid_this_level[0] ^ uid_this_level[1] ^ uid_this_level[2] ^ uid_this_level[3] - self.print_debug("BCC calc: %x" % bcc_calc) - if (bcc_val != bcc_calc): - self.print_debug("Something went wrong, BCC does not match.") - return 0 - - # clear interrupts - self.mfrc630_clear_irq0() - self.mfrc630_clear_irq1() - - send_req[0] = cmd - send_req[1] = 0x70 - send_req[2] = uid_this_level[0] - send_req[3] = uid_this_level[1] - send_req[4] = uid_this_level[2] - send_req[5] = uid_this_level[3] - send_req[6] = bcc_calc - message_length = 7 - - # Ok, almost done now, we re-enable the CRC's - self.mfrc630_write_reg(MFRC630_REG_TXCRCPRESET, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_ON) - self.mfrc630_write_reg(MFRC630_REG_RXCRCCON, MFRC630_RECOM_14443A_CRC | MFRC630_CRC_ON) - - # reset the Tx and Rx registers (disable alignment, transmit full bytes) - self.mfrc630_write_reg(MFRC630_REG_TXDATANUM, (known_bits % 8) | MFRC630_TXDATANUM_DATAEN) - rxalign = 0 - self.mfrc630_write_reg(MFRC630_REG_RXBITCTRL, (0 << 7) | (rxalign << 4)) - - # actually send it! - self.mfrc630_cmd_transceive(send_req) - self.print_debug("send_req %d long: " % message_length) - self.mfrc630_print_block(send_req, message_length) - - # Block until we are done... - irq1_value = 0 - while not (irq1_value & (1 << timer_for_timeout)): - irq1_value = self.mfrc630_irq1() - if (irq1_value & MFRC630_IRQ1_GLOBAL_IRQ): # either ERR_IRQ or RX_IRQ - break # stop polling irq1 and quit the timeout loop. - self.mfrc630_cmd_idle() - - # Check the source of exiting the loop. - irq0_value = self.mfrc630_irq0() - self.print_debug("irq0: %x" % irq0_value) - if irq0_value & MFRC630_IRQ0_ERR_IRQ: - # Check what kind of error. - error = self.mfrc630_read_reg(MFRC630_REG_ERROR) - self.print_debug("error: %x" % error) - if error & MFRC630_ERROR_COLLDET: - # a collision was detected with NVB=0x70, should never happen. - self.print_debug("a collision was detected with NVB=0x70, should never happen.") - return 0 - # Read the sak answer from the fifo. - sak_len = self.mfrc630_fifo_length() - self.print_debug("sak_len: %x" % sak_len) - if sak_len != 1: - return 0 - - sak_value = self.mfrc630_read_fifo(sak_len) - - self.print_debug("SAK answer: ") - self.mfrc630_print_block(sak_value, 1) - - if (sak_value[0] & (1 << 2)): - # UID not yet complete, continue with next cascade. - # This also means the 0'th byte of the UID in this level was CT, so we - # have to shift all bytes when moving to uid from uid_this_level. - for UIDn in range(0, 3): - # uid_this_level[UIDn] = uid_this_level[UIDn + 1]; - uid[(cascade_level - 1) * 3 + UIDn] = uid_this_level[UIDn + 1] - else: - # Done according so SAK! - # Add the bytes at this level to the UID. - for UIDn in range(0, 4): - uid[(cascade_level - 1) * 3 + UIDn] = uid_this_level[UIDn]; - - # Finally, return the length of the UID that's now at the uid "pointer". - return cascade_level * 3 + 1; - - self.print_debug("Exit cascade loop nr. %d: " % cascade_level) - self.mfrc630_print_block(uid, 10) - - return 0 # getting a UID failed. - - def mfrc630_MF_auth(self, uid, key_type, block): - # Enable the right interrupts. - - # configure a timeout timer. - timer_for_timeout = 0 # should match the enabled interrupt. - - # According to datasheet Interrupt on idle and timer with MFAUTHENT, but lets - # include ERROR as well. - self.mfrc630_write_reg(MFRC630_REG_IRQ0EN, MFRC630_IRQ0EN_IDLE_IRQEN | MFRC630_IRQ0EN_ERR_IRQEN) - self.mfrc630_write_reg(MFRC630_REG_IRQ1EN, MFRC630_IRQ1EN_TIMER0_IRQEN) # only trigger on timer for irq1 - - # Set timer to 221 kHz clock, start at the end of Tx. - self.mfrc630_timer_set_control(timer_for_timeout, MFRC630_TCONTROL_CLK_211KHZ | MFRC630_TCONTROL_START_TX_END) - # Frame waiting time: FWT = (256 x 16/fc) x 2 FWI - # FWI defaults to four... so that would mean wait for a maximum of ~ 5ms - - self.mfrc630_timer_set_reload(timer_for_timeout, 2000) # 2000 ticks of 5 usec is 10 ms. - self.mfrc630_timer_set_value(timer_for_timeout, 2000) - - irq1_value = 0 - - self.mfrc630_clear_irq0() # clear irq0 - self.mfrc630_clear_irq1() # clear irq1 - - # start the authentication procedure. - self.mfrc630_cmd_auth(key_type, block, uid) - - # block until we are done - while not (irq1_value & (1 << timer_for_timeout)): - irq1_value = self.mfrc630_irq1() - if (irq1_value & MFRC630_IRQ1_GLOBAL_IRQ): - break # stop polling irq1 and quit the timeout loop. - - if (irq1_value & (1 << timer_for_timeout)): - # this indicates a timeout - return 0 # we have no authentication - - # status is always valid, it is set to 0 in case of authentication failure. - status = self.mfrc630_read_reg(MFRC630_REG_STATUS) - return (status & MFRC630_STATUS_CRYPTO1_ON) - - def mfrc630_MF_deauth(self): - self.mfrc630_write_reg(MFRC630_REG_STATUS, 0) - - def format_block(self, block, length): - ret_val = "" - for i in range(0, length): - if (block[i] < 16): - ret_val += ("0%x " % block[i]) - else: - ret_val += ("%x " % block[i]) - return ret_val.upper() diff --git a/pybytes/pyscan/lib/pycoproc.py b/pybytes/pyscan/lib/pycoproc.py deleted file mode 100644 index 0b7772b..0000000 --- a/pybytes/pyscan/lib/pycoproc.py +++ /dev/null @@ -1,294 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from machine import Pin -from machine import I2C -import time -import pycom - -__version__ = '0.0.2' - -""" PIC MCU wakeup reason types """ -WAKE_REASON_ACCELEROMETER = 1 -WAKE_REASON_PUSH_BUTTON = 2 -WAKE_REASON_TIMER = 4 -WAKE_REASON_INT_PIN = 8 - -class Pycoproc: - """ class for handling the interaction with PIC MCU """ - - I2C_SLAVE_ADDR = const(8) - - CMD_PEEK = const(0x0) - CMD_POKE = const(0x01) - CMD_MAGIC = const(0x02) - CMD_HW_VER = const(0x10) - CMD_FW_VER = const(0x11) - CMD_PROD_ID = const(0x12) - CMD_SETUP_SLEEP = const(0x20) - CMD_GO_SLEEP = const(0x21) - CMD_CALIBRATE = const(0x22) - CMD_BAUD_CHANGE = const(0x30) - CMD_DFU = const(0x31) - - REG_CMD = const(0) - REG_ADDRL = const(1) - REG_ADDRH = const(2) - REG_AND = const(3) - REG_OR = const(4) - REG_XOR = const(5) - - ANSELA_ADDR = const(0x18C) - ANSELB_ADDR = const(0x18D) - ANSELC_ADDR = const(0x18E) - - ADCON0_ADDR = const(0x9D) - ADCON1_ADDR = const(0x9E) - - IOCAP_ADDR = const(0x391) - IOCAN_ADDR = const(0x392) - - INTCON_ADDR = const(0x0B) - OPTION_REG_ADDR = const(0x95) - - _ADCON0_CHS_POSN = const(0x02) - _ADCON0_ADON_MASK = const(0x01) - _ADCON1_ADCS_POSN = const(0x04) - _ADCON0_GO_nDONE_MASK = const(0x02) - - ADRESL_ADDR = const(0x09B) - ADRESH_ADDR = const(0x09C) - - TRISC_ADDR = const(0x08E) - - PORTA_ADDR = const(0x00C) - PORTC_ADDR = const(0x00E) - - WPUA_ADDR = const(0x20C) - - WAKE_REASON_ADDR = const(0x064C) - MEMORY_BANK_ADDR = const(0x0620) - - PCON_ADDR = const(0x096) - STATUS_ADDR = const(0x083) - - EXP_RTC_PERIOD = const(7000) - - def __init__(self, i2c=None, sda='P22', scl='P21'): - if i2c is not None: - self.i2c = i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.sda = sda - self.scl = scl - self.clk_cal_factor = 1 - self.reg = bytearray(6) - self.wake_int = False - self.wake_int_pin = False - self.wake_int_pin_rising_edge = True - - # Make sure we are inserted into the - # correct board and can talk to the PIC - try: - self.read_fw_version() - except Exception as e: - raise Exception('Board not detected: {}'.format(e)) - - # init the ADC for the battery measurements - self.poke_memory(ANSELC_ADDR, 1 << 2) - self.poke_memory(ADCON0_ADDR, (0x06 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) - self.poke_memory(ADCON1_ADDR, (0x06 << _ADCON1_ADCS_POSN)) - # enable the pull-up on RA3 - self.poke_memory(WPUA_ADDR, (1 << 3)) - # make RC5 an input - self.set_bits_in_memory(TRISC_ADDR, 1 << 5) - # set RC6 and RC7 as outputs and enable power to the sensors and the GPS - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 6)) - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - - if self.read_fw_version() < 6: - raise ValueError('Firmware out of date') - - - def _write(self, data, wait=True): - self.i2c.writeto(I2C_SLAVE_ADDR, data) - if wait: - self._wait() - - def _read(self, size): - return self.i2c.readfrom(I2C_SLAVE_ADDR, size + 1)[1:(size + 1)] - - def _wait(self): - count = 0 - time.sleep_us(10) - while self.i2c.readfrom(I2C_SLAVE_ADDR, 1)[0] != 0xFF: - time.sleep_us(100) - count += 1 - if (count > 500): # timeout after 50ms - raise Exception('Board timeout') - - def _send_cmd(self, cmd): - self._write(bytes([cmd])) - - def read_hw_version(self): - self._send_cmd(CMD_HW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_fw_version(self): - self._send_cmd(CMD_FW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_product_id(self): - self._send_cmd(CMD_PROD_ID) - d = self._read(2) - return (d[1] << 8) + d[0] - - def peek_memory(self, addr): - self._write(bytes([CMD_PEEK, addr & 0xFF, (addr >> 8) & 0xFF])) - return self._read(1)[0] - - def poke_memory(self, addr, value): - self._write(bytes([CMD_POKE, addr & 0xFF, (addr >> 8) & 0xFF, value & 0xFF])) - - def magic_write_read(self, addr, _and=0xFF, _or=0, _xor=0): - self._write(bytes([CMD_MAGIC, addr & 0xFF, (addr >> 8) & 0xFF, _and & 0xFF, _or & 0xFF, _xor & 0xFF])) - return self._read(1)[0] - - def toggle_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _xor=bits) - - def mask_bits_in_memory(self, addr, mask): - self.magic_write_read(addr, _and=mask) - - def set_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _or=bits) - - def get_wake_reason(self): - """ returns the wakeup reason, a value out of constants WAKE_REASON_* """ - return self.peek_memory(WAKE_REASON_ADDR) - - def get_sleep_remaining(self): - """ returns the remaining time from sleep, as an interrupt (wakeup source) might have triggered """ - c3 = self.peek_memory(WAKE_REASON_ADDR + 3) - c2 = self.peek_memory(WAKE_REASON_ADDR + 2) - c1 = self.peek_memory(WAKE_REASON_ADDR + 1) - time_device_s = (c3 << 16) + (c2 << 8) + c1 - # this time is from PIC internal oscilator, so it needs to be adjusted with the calibration value - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_device_s / self.clk_cal_factor) + 0.5) # 0.5 used for round - return time_s - - def setup_sleep(self, time_s): - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_s * self.clk_cal_factor) + 0.5) # round to the nearest integer - if time_s >= 2**(8*3): - time_s = 2**(8*3)-1 - self._write(bytes([CMD_SETUP_SLEEP, time_s & 0xFF, (time_s >> 8) & 0xFF, (time_s >> 16) & 0xFF])) - - def go_to_sleep(self, gps=True): - # enable or disable back-up power to the GPS receiver - if gps: - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) - else: - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) - # disable the ADC - self.poke_memory(ADCON0_ADDR, 0) - - if self.wake_int: - # Don't touch RA3, RA5 or RC1 so that interrupt wake-up works - self.poke_memory(ANSELA_ADDR, ~((1 << 3) | (1 << 5))) - self.poke_memory(ANSELC_ADDR, ~((1 << 6) | (1 << 7) | (1 << 1))) - else: - # disable power to the accelerometer, and don't touch RA3 so that button wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~(1 << 7)) - - self.poke_memory(ANSELB_ADDR, 0xFF) - - # check if INT pin (PIC RC1), should be used for wakeup - if self.wake_int_pin: - if self.wake_int_pin_rising_edge: - self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin - else: - self.mask_bits_in_memory(OPTION_REG_ADDR, ~(1 << 6)) # falling edge of INT pin - self.mask_bits_in_memory(ANSELC_ADDR, ~(1 << 1)) # disable analog function for RC1 pin - self.set_bits_in_memory(TRISC_ADDR, 1 << 1) # make RC1 input pin - self.mask_bits_in_memory(INTCON_ADDR, ~(1 << 1)) # clear INTF - self.set_bits_in_memory(INTCON_ADDR, 1 << 4) # enable interrupt; set INTE) - - self._write(bytes([CMD_GO_SLEEP]), wait=False) - # kill the run pin - Pin('P3', mode=Pin.OUT, value=0) - - def calibrate_rtc(self): - # the 1.024 factor is because the PIC LF operates at 31 KHz - # WDT has a frequency divider to generate 1 ms - # and then there is a binary prescaler, e.g., 1, 2, 4 ... 512, 1024 ms - # hence the need for the constant - self._write(bytes([CMD_CALIBRATE]), wait=False) - self.i2c.deinit() - Pin('P21', mode=Pin.IN) - pulses = pycom.pulses_get('P21', 100) - self.i2c.init(mode=I2C.MASTER, pins=(self.sda, self.scl)) - idx = 0 - for i in range(len(pulses)): - if pulses[i][1] > EXP_RTC_PERIOD: - idx = i - break - try: - period = pulses[idx][1] - pulses[(idx - 1)][1] - except: - period = 0 - if period > 0: - self.clk_cal_factor = (EXP_RTC_PERIOD / period) * (1000 / 1024) - if self.clk_cal_factor > 1.25 or self.clk_cal_factor < 0.75: - self.clk_cal_factor = 1 - - def button_pressed(self): - button = self.peek_memory(PORTA_ADDR) & (1 << 3) - return not button - - def read_battery_voltage(self): - self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) - time.sleep_us(50) - while self.peek_memory(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: - time.sleep_us(100) - adc_val = (self.peek_memory(ADRESH_ADDR) << 2) + (self.peek_memory(ADRESL_ADDR) >> 6) - return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET - - def setup_int_wake_up(self, rising, falling): - """ rising is for activity detection, falling for inactivity """ - wake_int = False - if rising: - self.set_bits_in_memory(IOCAP_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAP_ADDR, ~(1 << 5)) - - if falling: - self.set_bits_in_memory(IOCAN_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAN_ADDR, ~(1 << 5)) - self.wake_int = wake_int - - def setup_int_pin_wake_up(self, rising_edge = True): - """ allows wakeup to be made by the INT pin (PIC -RC1) """ - self.wake_int_pin = True - self.wake_int_pin_rising_edge = rising_edge diff --git a/pybytes/pyscan/lib/pyscan.py b/pybytes/pyscan/lib/pyscan.py deleted file mode 100644 index 40a1830..0000000 --- a/pybytes/pyscan/lib/pyscan.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from pycoproc import Pycoproc - -__version__ = '1.0.0' - -class Pyscan(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, i2c, sda, scl) \ No newline at end of file diff --git a/pybytes/pysense/lib/LIS2HH12.py b/pybytes/pysense/lib/LIS2HH12.py deleted file mode 100644 index 49a6b5a..0000000 --- a/pybytes/pysense/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (thresold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (thresold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used thresold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pybytes/pysense/lib/LTR329ALS01.py b/pybytes/pysense/lib/LTR329ALS01.py deleted file mode 100644 index 49e3439..0000000 --- a/pybytes/pysense/lib/LTR329ALS01.py +++ /dev/null @@ -1,80 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C - -class LTR329ALS01: - ALS_I2CADDR = const(0x29) # The device's I2C address - - ALS_CONTR_REG = const(0x80) - ALS_MEAS_RATE_REG = const(0x85) - - ALS_DATA_CH1_LOW = const(0x88) - ALS_DATA_CH1_HIGH = const(0x89) - ALS_DATA_CH0_LOW = const(0x8A) - ALS_DATA_CH0_HIGH = const(0x8B) - - ALS_GAIN_1X = const(0x00) - ALS_GAIN_2X = const(0x01) - ALS_GAIN_4X = const(0x02) - ALS_GAIN_8X = const(0x03) - ALS_GAIN_48X = const(0x06) - ALS_GAIN_96X = const(0x07) - - ALS_INT_50 = const(0x01) - ALS_INT_100 = const(0x00) - ALS_INT_150 = const(0x04) - ALS_INT_200 = const(0x02) - ALS_INT_250 = const(0x05) - ALS_INT_300 = const(0x06) - ALS_INT_350 = const(0x07) - ALS_INT_400 = const(0x03) - - ALS_RATE_50 = const(0x00) - ALS_RATE_100 = const(0x01) - ALS_RATE_200 = const(0x02) - ALS_RATE_500 = const(0x03) - ALS_RATE_1000 = const(0x04) - ALS_RATE_2000 = const(0x05) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21', gain = ALS_GAIN_1X, integration = ALS_INT_100, rate = ALS_RATE_500): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - contr = self._getContr(gain) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_CONTR_REG, bytearray([contr])) - - measrate = self._getMeasRate(integration, rate) - self.i2c.writeto_mem(ALS_I2CADDR, ALS_MEAS_RATE_REG, bytearray([measrate])) - - time.sleep(0.01) - - def _getContr(self, gain): - return ((gain & 0x07) << 2) + 0x01 - - def _getMeasRate(self, integration, rate): - return ((integration & 0x07) << 3) + (rate & 0x07) - - def _getWord(self, high, low): - return ((high & 0xFF) << 8) + (low & 0xFF) - - def light(self): - ch1low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_LOW, 1) - ch1high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH1_HIGH, 1) - data1 = int(self._getWord(ch1high[0], ch1low[0])) - - ch0low = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_LOW, 1) - ch0high = self.i2c.readfrom_mem(ALS_I2CADDR , ALS_DATA_CH0_HIGH, 1) - data0 = int(self._getWord(ch0high[0], ch0low[0])) - - return (data0, data1) diff --git a/pybytes/pysense/lib/MPL3115A2.py b/pybytes/pysense/lib/MPL3115A2.py deleted file mode 100644 index 28a4297..0000000 --- a/pybytes/pysense/lib/MPL3115A2.py +++ /dev/null @@ -1,129 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C - -ALTITUDE = const(0) -PRESSURE = const(1) - -class MPL3115A2exception(Exception): - pass - -class MPL3115A2: - MPL3115_I2CADDR = const(0x60) - MPL3115_STATUS = const(0x00) - MPL3115_PRESSURE_DATA_MSB = const(0x01) - MPL3115_PRESSURE_DATA_CSB = const(0x02) - MPL3115_PRESSURE_DATA_LSB = const(0x03) - MPL3115_TEMP_DATA_MSB = const(0x04) - MPL3115_TEMP_DATA_LSB = const(0x05) - MPL3115_DR_STATUS = const(0x06) - MPL3115_DELTA_DATA = const(0x07) - MPL3115_WHO_AM_I = const(0x0c) - MPL3115_FIFO_STATUS = const(0x0d) - MPL3115_FIFO_DATA = const(0x0e) - MPL3115_FIFO_SETUP = const(0x0e) - MPL3115_TIME_DELAY = const(0x10) - MPL3115_SYS_MODE = const(0x11) - MPL3115_INT_SORCE = const(0x12) - MPL3115_PT_DATA_CFG = const(0x13) - MPL3115_BAR_IN_MSB = const(0x14) - MPL3115_P_ARLARM_MSB = const(0x16) - MPL3115_T_ARLARM = const(0x18) - MPL3115_P_ARLARM_WND_MSB = const(0x19) - MPL3115_T_ARLARM_WND = const(0x1b) - MPL3115_P_MIN_DATA = const(0x1c) - MPL3115_T_MIN_DATA = const(0x1f) - MPL3115_P_MAX_DATA = const(0x21) - MPL3115_T_MAX_DATA = const(0x24) - MPL3115_CTRL_REG1 = const(0x26) - MPL3115_CTRL_REG2 = const(0x27) - MPL3115_CTRL_REG3 = const(0x28) - MPL3115_CTRL_REG4 = const(0x29) - MPL3115_CTRL_REG5 = const(0x2a) - MPL3115_OFFSET_P = const(0x2b) - MPL3115_OFFSET_T = const(0x2c) - MPL3115_OFFSET_H = const(0x2d) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21', mode = PRESSURE): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.STA_reg = bytearray(1) - self.mode = mode - - if self.mode is PRESSURE: - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0x38])) # barometer mode, not raw, oversampling 128, minimum time 512 ms - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_PT_DATA_CFG, bytes([0x07])) # no events detected - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0x39])) # active - elif self.mode is ALTITUDE: - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0xB8])) # altitude mode, not raw, oversampling 128, minimum time 512 ms - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_PT_DATA_CFG, bytes([0x07])) # no events detected - self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0xB9])) # active - else: - raise MPL3115A2exception("Invalid Mode MPL3115A2") - - if self._read_status(): - pass - else: - raise MPL3115A2exception("Error with MPL3115A2") - - def _read_status(self): - while True: - self.i2c.readfrom_mem_into(MPL3115_I2CADDR, MPL3115_STATUS, self.STA_reg) - - if(self.STA_reg[0] == 0): - time.sleep(0.01) - pass - elif(self.STA_reg[0] & 0x04) == 4: - return True - else: - return False - - def pressure(self): - if self.mode == ALTITUDE: - raise MPL3115A2exception("Incorrect Measurement Mode MPL3115A2") - - OUT_P_MSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_MSB,1) - OUT_P_CSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_CSB,1) - OUT_P_LSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_LSB,1) - - return float((OUT_P_MSB[0] << 10) + (OUT_P_CSB[0] << 2) + ((OUT_P_LSB[0] >> 6) & 0x03) + ((OUT_P_LSB[0] >> 4) & 0x03) / 4.0) - - def altitude(self): - if self.mode == PRESSURE: - raise MPL3115A2exception("Incorrect Measurement Mode MPL3115A2") - - OUT_P_MSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_MSB,1) - OUT_P_CSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_CSB,1) - OUT_P_LSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_PRESSURE_DATA_LSB,1) - - alt_int = (OUT_P_MSB[0] << 8) + (OUT_P_CSB[0]) - alt_frac = ((OUT_P_LSB[0] >> 4) & 0x0F) - - if alt_int > 32767: - alt_int -= 65536 - - return float(alt_int + alt_frac / 16.0) - - def temperature(self): - OUT_T_MSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_TEMP_DATA_MSB,1) - OUT_T_LSB = self.i2c.readfrom_mem(MPL3115_I2CADDR, MPL3115_TEMP_DATA_LSB,1) - - temp_int = OUT_T_MSB[0] - temp_frac = OUT_T_LSB[0] - - if temp_int > 127: - temp_int -= 256 - - return float(temp_int + temp_frac / 256.0) diff --git a/pybytes/pysense/lib/SI7006A20.py b/pybytes/pysense/lib/SI7006A20.py deleted file mode 100644 index d9a4025..0000000 --- a/pybytes/pysense/lib/SI7006A20.py +++ /dev/null @@ -1,118 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import time -from machine import I2C -import math - -__version__ = '0.0.2' - -class SI7006A20: - """ class for handling the temperature sensor SI7006-A20 - +/- 1 deg C error for temperature - +/- 5% error for relative humidity - datasheet available at https://www.silabs.com/documents/public/data-sheets/Si7006-A20.pdf """ - - SI7006A20_I2C_ADDR = const(0x40) - - TEMP_NOHOLDMASTER = const(0xF3) - HUMD_NOHOLDMASTER = const(0xF5) - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - def _getWord(self, high, low): - return ((high & 0xFF) << 8) + (low & 0xFF) - - def temperature(self): - """ obtaining the temperature(degrees Celsius) measured by sensor """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xF3])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 3) - #print("CRC Raw temp data: " + hex(data[0]*65536 + data[1]*256 + data[2])) - data = self._getWord(data[0], data[1]) - temp = ((175.72 * data) / 65536.0) - 46.85 - return temp - - def humidity(self): - """ obtaining the relative humidity(%) measured by sensor """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xF5])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 2) - data = self._getWord(data[0], data[1]) - humidity = ((125.0 * data) / 65536.0) - 6.0 - return humidity - - def read_user_reg(self): - """ reading the user configuration register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xE7])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return data[0] - - def read_heater_reg(self): - """ reading the heater configuration register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0x11])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return data[0] - - def read_electronic_id(self): - """ reading electronic identifier """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xFA]) + bytearray([0x0F])) - time.sleep(0.5) - sna = self.i2c.readfrom(SI7006A20_I2C_ADDR, 4) - time.sleep(0.1) - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xFC]) + bytearray([0xC9])) - time.sleep(0.5) - snb = self.i2c.readfrom(SI7006A20_I2C_ADDR, 4) - return [sna[0], sna[1], sna[2], sna[3], snb[0], snb[1], snb[2], snb[3]] - - def read_firmware(self): - """ reading firmware version """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0x84])+ bytearray([0xB8])) - time.sleep(0.5) - fw = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return fw[0] - - def read_reg(self, reg_addr): - """ reading a register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([reg_addr])) - time.sleep(0.5) - data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) - return data[0] - - def write_reg(self, reg_addr, value): - """ writing a register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([reg_addr])+bytearray([value])) - time.sleep(0.1) - - def dew_point(self): - """ computing the dew pointe temperature (deg C) for the current Temperature and Humidity measured pair - at dew-point temperature the relative humidity is 100% """ - temp = self.temperature() - humid = self.humidity() - h = (math.log(humid, 10) - 2) / 0.4343 + (17.62 * temp) / (243.12 + temp) - dew_p = 243.12 * h / (17.62 - h) - return dew_p - - def humid_ambient(self, t_ambient, dew_p = None): - """ returns the relative humidity compensated for the current Ambient temperature - for ex: T-Ambient is 24.4 degC, but sensor indicates Temperature = 31.65 degC and Humidity = 47.3% - -> then the actual Relative Humidity is 72.2% - this is computed because the dew-point should be the same """ - if dew_p is None: - dew_p = self.dew_point() - h = 17.62 * dew_p / (243.12 + dew_p) - h_ambient = math.pow(10, (h - (17.62 * t_ambient) / (243.12 + t_ambient)) * 0.4343 + 2) - return h_ambient diff --git a/pybytes/pysense/lib/pycoproc.py b/pybytes/pysense/lib/pycoproc.py deleted file mode 100644 index 0b7772b..0000000 --- a/pybytes/pysense/lib/pycoproc.py +++ /dev/null @@ -1,294 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from machine import Pin -from machine import I2C -import time -import pycom - -__version__ = '0.0.2' - -""" PIC MCU wakeup reason types """ -WAKE_REASON_ACCELEROMETER = 1 -WAKE_REASON_PUSH_BUTTON = 2 -WAKE_REASON_TIMER = 4 -WAKE_REASON_INT_PIN = 8 - -class Pycoproc: - """ class for handling the interaction with PIC MCU """ - - I2C_SLAVE_ADDR = const(8) - - CMD_PEEK = const(0x0) - CMD_POKE = const(0x01) - CMD_MAGIC = const(0x02) - CMD_HW_VER = const(0x10) - CMD_FW_VER = const(0x11) - CMD_PROD_ID = const(0x12) - CMD_SETUP_SLEEP = const(0x20) - CMD_GO_SLEEP = const(0x21) - CMD_CALIBRATE = const(0x22) - CMD_BAUD_CHANGE = const(0x30) - CMD_DFU = const(0x31) - - REG_CMD = const(0) - REG_ADDRL = const(1) - REG_ADDRH = const(2) - REG_AND = const(3) - REG_OR = const(4) - REG_XOR = const(5) - - ANSELA_ADDR = const(0x18C) - ANSELB_ADDR = const(0x18D) - ANSELC_ADDR = const(0x18E) - - ADCON0_ADDR = const(0x9D) - ADCON1_ADDR = const(0x9E) - - IOCAP_ADDR = const(0x391) - IOCAN_ADDR = const(0x392) - - INTCON_ADDR = const(0x0B) - OPTION_REG_ADDR = const(0x95) - - _ADCON0_CHS_POSN = const(0x02) - _ADCON0_ADON_MASK = const(0x01) - _ADCON1_ADCS_POSN = const(0x04) - _ADCON0_GO_nDONE_MASK = const(0x02) - - ADRESL_ADDR = const(0x09B) - ADRESH_ADDR = const(0x09C) - - TRISC_ADDR = const(0x08E) - - PORTA_ADDR = const(0x00C) - PORTC_ADDR = const(0x00E) - - WPUA_ADDR = const(0x20C) - - WAKE_REASON_ADDR = const(0x064C) - MEMORY_BANK_ADDR = const(0x0620) - - PCON_ADDR = const(0x096) - STATUS_ADDR = const(0x083) - - EXP_RTC_PERIOD = const(7000) - - def __init__(self, i2c=None, sda='P22', scl='P21'): - if i2c is not None: - self.i2c = i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.sda = sda - self.scl = scl - self.clk_cal_factor = 1 - self.reg = bytearray(6) - self.wake_int = False - self.wake_int_pin = False - self.wake_int_pin_rising_edge = True - - # Make sure we are inserted into the - # correct board and can talk to the PIC - try: - self.read_fw_version() - except Exception as e: - raise Exception('Board not detected: {}'.format(e)) - - # init the ADC for the battery measurements - self.poke_memory(ANSELC_ADDR, 1 << 2) - self.poke_memory(ADCON0_ADDR, (0x06 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) - self.poke_memory(ADCON1_ADDR, (0x06 << _ADCON1_ADCS_POSN)) - # enable the pull-up on RA3 - self.poke_memory(WPUA_ADDR, (1 << 3)) - # make RC5 an input - self.set_bits_in_memory(TRISC_ADDR, 1 << 5) - # set RC6 and RC7 as outputs and enable power to the sensors and the GPS - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 6)) - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - - if self.read_fw_version() < 6: - raise ValueError('Firmware out of date') - - - def _write(self, data, wait=True): - self.i2c.writeto(I2C_SLAVE_ADDR, data) - if wait: - self._wait() - - def _read(self, size): - return self.i2c.readfrom(I2C_SLAVE_ADDR, size + 1)[1:(size + 1)] - - def _wait(self): - count = 0 - time.sleep_us(10) - while self.i2c.readfrom(I2C_SLAVE_ADDR, 1)[0] != 0xFF: - time.sleep_us(100) - count += 1 - if (count > 500): # timeout after 50ms - raise Exception('Board timeout') - - def _send_cmd(self, cmd): - self._write(bytes([cmd])) - - def read_hw_version(self): - self._send_cmd(CMD_HW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_fw_version(self): - self._send_cmd(CMD_FW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_product_id(self): - self._send_cmd(CMD_PROD_ID) - d = self._read(2) - return (d[1] << 8) + d[0] - - def peek_memory(self, addr): - self._write(bytes([CMD_PEEK, addr & 0xFF, (addr >> 8) & 0xFF])) - return self._read(1)[0] - - def poke_memory(self, addr, value): - self._write(bytes([CMD_POKE, addr & 0xFF, (addr >> 8) & 0xFF, value & 0xFF])) - - def magic_write_read(self, addr, _and=0xFF, _or=0, _xor=0): - self._write(bytes([CMD_MAGIC, addr & 0xFF, (addr >> 8) & 0xFF, _and & 0xFF, _or & 0xFF, _xor & 0xFF])) - return self._read(1)[0] - - def toggle_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _xor=bits) - - def mask_bits_in_memory(self, addr, mask): - self.magic_write_read(addr, _and=mask) - - def set_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _or=bits) - - def get_wake_reason(self): - """ returns the wakeup reason, a value out of constants WAKE_REASON_* """ - return self.peek_memory(WAKE_REASON_ADDR) - - def get_sleep_remaining(self): - """ returns the remaining time from sleep, as an interrupt (wakeup source) might have triggered """ - c3 = self.peek_memory(WAKE_REASON_ADDR + 3) - c2 = self.peek_memory(WAKE_REASON_ADDR + 2) - c1 = self.peek_memory(WAKE_REASON_ADDR + 1) - time_device_s = (c3 << 16) + (c2 << 8) + c1 - # this time is from PIC internal oscilator, so it needs to be adjusted with the calibration value - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_device_s / self.clk_cal_factor) + 0.5) # 0.5 used for round - return time_s - - def setup_sleep(self, time_s): - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_s * self.clk_cal_factor) + 0.5) # round to the nearest integer - if time_s >= 2**(8*3): - time_s = 2**(8*3)-1 - self._write(bytes([CMD_SETUP_SLEEP, time_s & 0xFF, (time_s >> 8) & 0xFF, (time_s >> 16) & 0xFF])) - - def go_to_sleep(self, gps=True): - # enable or disable back-up power to the GPS receiver - if gps: - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) - else: - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) - # disable the ADC - self.poke_memory(ADCON0_ADDR, 0) - - if self.wake_int: - # Don't touch RA3, RA5 or RC1 so that interrupt wake-up works - self.poke_memory(ANSELA_ADDR, ~((1 << 3) | (1 << 5))) - self.poke_memory(ANSELC_ADDR, ~((1 << 6) | (1 << 7) | (1 << 1))) - else: - # disable power to the accelerometer, and don't touch RA3 so that button wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~(1 << 7)) - - self.poke_memory(ANSELB_ADDR, 0xFF) - - # check if INT pin (PIC RC1), should be used for wakeup - if self.wake_int_pin: - if self.wake_int_pin_rising_edge: - self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin - else: - self.mask_bits_in_memory(OPTION_REG_ADDR, ~(1 << 6)) # falling edge of INT pin - self.mask_bits_in_memory(ANSELC_ADDR, ~(1 << 1)) # disable analog function for RC1 pin - self.set_bits_in_memory(TRISC_ADDR, 1 << 1) # make RC1 input pin - self.mask_bits_in_memory(INTCON_ADDR, ~(1 << 1)) # clear INTF - self.set_bits_in_memory(INTCON_ADDR, 1 << 4) # enable interrupt; set INTE) - - self._write(bytes([CMD_GO_SLEEP]), wait=False) - # kill the run pin - Pin('P3', mode=Pin.OUT, value=0) - - def calibrate_rtc(self): - # the 1.024 factor is because the PIC LF operates at 31 KHz - # WDT has a frequency divider to generate 1 ms - # and then there is a binary prescaler, e.g., 1, 2, 4 ... 512, 1024 ms - # hence the need for the constant - self._write(bytes([CMD_CALIBRATE]), wait=False) - self.i2c.deinit() - Pin('P21', mode=Pin.IN) - pulses = pycom.pulses_get('P21', 100) - self.i2c.init(mode=I2C.MASTER, pins=(self.sda, self.scl)) - idx = 0 - for i in range(len(pulses)): - if pulses[i][1] > EXP_RTC_PERIOD: - idx = i - break - try: - period = pulses[idx][1] - pulses[(idx - 1)][1] - except: - period = 0 - if period > 0: - self.clk_cal_factor = (EXP_RTC_PERIOD / period) * (1000 / 1024) - if self.clk_cal_factor > 1.25 or self.clk_cal_factor < 0.75: - self.clk_cal_factor = 1 - - def button_pressed(self): - button = self.peek_memory(PORTA_ADDR) & (1 << 3) - return not button - - def read_battery_voltage(self): - self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) - time.sleep_us(50) - while self.peek_memory(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: - time.sleep_us(100) - adc_val = (self.peek_memory(ADRESH_ADDR) << 2) + (self.peek_memory(ADRESL_ADDR) >> 6) - return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET - - def setup_int_wake_up(self, rising, falling): - """ rising is for activity detection, falling for inactivity """ - wake_int = False - if rising: - self.set_bits_in_memory(IOCAP_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAP_ADDR, ~(1 << 5)) - - if falling: - self.set_bits_in_memory(IOCAN_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAN_ADDR, ~(1 << 5)) - self.wake_int = wake_int - - def setup_int_pin_wake_up(self, rising_edge = True): - """ allows wakeup to be made by the INT pin (PIC -RC1) """ - self.wake_int_pin = True - self.wake_int_pin_rising_edge = rising_edge diff --git a/pybytes/pysense/lib/pysense.py b/pybytes/pysense/lib/pysense.py deleted file mode 100644 index 04d31e7..0000000 --- a/pybytes/pysense/lib/pysense.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from pycoproc import Pycoproc - -__version__ = '1.4.0' - -class Pysense(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, i2c, sda, scl) diff --git a/pybytes/pytrack/lib/L76GNSS.py b/pybytes/pytrack/lib/L76GNSS.py deleted file mode 100644 index 8b6fca6..0000000 --- a/pybytes/pytrack/lib/L76GNSS.py +++ /dev/null @@ -1,96 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from machine import Timer -import time -import gc -import binascii - - -class L76GNSS: - - GPS_I2CADDR = const(0x10) - - def __init__(self, pytrack=None, sda='P22', scl='P21', timeout=None): - if pytrack is not None: - self.i2c = pytrack.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.chrono = Timer.Chrono() - - self.timeout = timeout - self.timeout_status = True - - self.reg = bytearray(1) - self.i2c.writeto(GPS_I2CADDR, self.reg) - - def _read(self): - self.reg = self.i2c.readfrom(GPS_I2CADDR, 64) - return self.reg - - def _convert_coords(self, gngll_s): - lat = gngll_s[1] - lat_d = (float(lat) // 100) + ((float(lat) % 100) / 60) - lon = gngll_s[3] - lon_d = (float(lon) // 100) + ((float(lon) % 100) / 60) - if gngll_s[2] == 'S': - lat_d *= -1 - if gngll_s[4] == 'W': - lon_d *= -1 - return(lat_d, lon_d) - - def coordinates(self, debug=False): - lat_d, lon_d, debug_timeout = None, None, False - if self.timeout is not None: - self.chrono.reset() - self.chrono.start() - nmea = b'' - while True: - if self.timeout is not None and self.chrono.read() >= self.timeout: - self.chrono.stop() - chrono_timeout = self.chrono.read() - self.chrono.reset() - self.timeout_status = False - debug_timeout = True - if not self.timeout_status: - gc.collect() - break - nmea += self._read().lstrip(b'\n\n').rstrip(b'\n\n') - gngll_idx = nmea.find(b'GNGLL') - gpgll_idx = nmea.find(b'GPGLL') - if gngll_idx < 0 and gpgll_idx >= 0: - gngll_idx = gpgll_idx - if gngll_idx >= 0: - gngll = nmea[gngll_idx:] - e_idx = gngll.find(b'\r\n') - if e_idx >= 0: - try: - gngll = gngll[:e_idx].decode('ascii') - gngll_s = gngll.split(',') - lat_d, lon_d = self._convert_coords(gngll_s) - except Exception: - pass - finally: - nmea = nmea[(gngll_idx + e_idx):] - gc.collect() - break - else: - gc.collect() - if len(nmea) > 410: # i suppose it can be safely changed to 82, which is longest NMEA frame - nmea = nmea[-5:] # $GNGL without last L - time.sleep(0.1) - self.timeout_status = True - if debug and debug_timeout: - print('GPS timed out after %f seconds' % (chrono_timeout)) - return(None, None) - else: - return(lat_d, lon_d) diff --git a/pybytes/pytrack/lib/LIS2HH12.py b/pybytes/pytrack/lib/LIS2HH12.py deleted file mode 100644 index 49a6b5a..0000000 --- a/pybytes/pytrack/lib/LIS2HH12.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import math -import time -import struct -from machine import Pin - - -FULL_SCALE_2G = const(0) -FULL_SCALE_4G = const(2) -FULL_SCALE_8G = const(3) - -ODR_POWER_DOWN = const(0) -ODR_10_HZ = const(1) -ODR_50_HZ = const(2) -ODR_100_HZ = const(3) -ODR_200_HZ = const(4) -ODR_400_HZ = const(5) -ODR_800_HZ = const(6) - -ACC_G_DIV = 1000 * 65536 - - -class LIS2HH12: - - ACC_I2CADDR = const(30) - - PRODUCTID_REG = const(0x0F) - CTRL1_REG = const(0x20) - CTRL2_REG = const(0x21) - CTRL3_REG = const(0x22) - CTRL4_REG = const(0x23) - CTRL5_REG = const(0x24) - ACC_X_L_REG = const(0x28) - ACC_X_H_REG = const(0x29) - ACC_Y_L_REG = const(0x2A) - ACC_Y_H_REG = const(0x2B) - ACC_Z_L_REG = const(0x2C) - ACC_Z_H_REG = const(0x2D) - ACT_THS = const(0x1E) - ACT_DUR = const(0x1F) - - SCALES = {FULL_SCALE_2G: 4000, FULL_SCALE_4G: 8000, FULL_SCALE_8G: 16000} - ODRS = [0, 10, 50, 100, 200, 400, 800] - - def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): - if pysense is not None: - self.i2c = pysense.i2c - else: - from machine import I2C - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.odr = 0 - self.full_scale = 0 - self.x = 0 - self.y = 0 - self.z = 0 - self.int_pin = None - self.act_dur = 0 - self.debounced = False - - whoami = self.i2c.readfrom_mem(ACC_I2CADDR , PRODUCTID_REG, 1) - if (whoami[0] != 0x41): - raise ValueError("LIS2HH12 not found") - - # enable acceleration readings at 50Hz - self.set_odr(ODR_50_HZ) - - # change the full-scale to 4g - self.set_full_scale(FULL_SCALE_4G) - - # set the interrupt pin as active low and open drain - self.set_register(CTRL5_REG, 3, 0, 3) - - # make a first read - self.acceleration() - - def acceleration(self): - x = self.i2c.readfrom_mem(ACC_I2CADDR , ACC_X_L_REG, 2) - self.x = struct.unpack(' self.SCALES[self.full_scale]: - error = "threshold %d exceeds full scale %d" % (thresold, self.SCALES[self.full_scale]) - print(error) - raise ValueError(error) - - if threshold < self.SCALES[self.full_scale] / 128: - error = "threshold %d below resolution %d" % (thresold, self.SCALES[self.full_scale]/128) - print(error) - raise ValueError(error) - - if duration > 255 * 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d exceeds max possible value %d" % (duration, 255 * 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - if duration < 1000 * 8 / self.ODRS[self.odr]: - error = "duration %d below resolution %d" % (duration, 1000 * 8 / self.ODRS[self.odr]) - print(error) - raise ValueError(error) - - _ths = int(127 * threshold / self.SCALES[self.full_scale]) & 0x7F - _dur = int((duration * self.ODRS[self.odr]) / 1000 / 8) - - self.i2c.writeto_mem(ACC_I2CADDR, ACT_THS, _ths) - self.i2c.writeto_mem(ACC_I2CADDR, ACT_DUR, _dur) - - # enable the activity/inactivity interrupt - self.set_register(CTRL3_REG, 1, 5, 1) - - self._user_handler = handler - self.int_pin = Pin('P13', mode=Pin.IN) - self.int_pin.callback(trigger=Pin.IRQ_FALLING | Pin.IRQ_RISING, handler=self._int_handler) - - # return actual used thresold and duration - return (_ths * self.SCALES[self.full_scale] / 128, _dur * 8 * 1000 / self.ODRS[self.odr]) - - def activity(self): - if not self.debounced: - time.sleep_ms(self.act_dur) - self.debounced = True - if self.int_pin(): - return True - return False - - def _int_handler(self, pin_o): - if self._user_handler is not None: - self._user_handler(pin_o) - else: - if pin_o(): - print('Activity interrupt') - else: - print('Inactivity interrupt') diff --git a/pybytes/pytrack/lib/pycoproc.py b/pybytes/pytrack/lib/pycoproc.py deleted file mode 100644 index 0b7772b..0000000 --- a/pybytes/pytrack/lib/pycoproc.py +++ /dev/null @@ -1,294 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from machine import Pin -from machine import I2C -import time -import pycom - -__version__ = '0.0.2' - -""" PIC MCU wakeup reason types """ -WAKE_REASON_ACCELEROMETER = 1 -WAKE_REASON_PUSH_BUTTON = 2 -WAKE_REASON_TIMER = 4 -WAKE_REASON_INT_PIN = 8 - -class Pycoproc: - """ class for handling the interaction with PIC MCU """ - - I2C_SLAVE_ADDR = const(8) - - CMD_PEEK = const(0x0) - CMD_POKE = const(0x01) - CMD_MAGIC = const(0x02) - CMD_HW_VER = const(0x10) - CMD_FW_VER = const(0x11) - CMD_PROD_ID = const(0x12) - CMD_SETUP_SLEEP = const(0x20) - CMD_GO_SLEEP = const(0x21) - CMD_CALIBRATE = const(0x22) - CMD_BAUD_CHANGE = const(0x30) - CMD_DFU = const(0x31) - - REG_CMD = const(0) - REG_ADDRL = const(1) - REG_ADDRH = const(2) - REG_AND = const(3) - REG_OR = const(4) - REG_XOR = const(5) - - ANSELA_ADDR = const(0x18C) - ANSELB_ADDR = const(0x18D) - ANSELC_ADDR = const(0x18E) - - ADCON0_ADDR = const(0x9D) - ADCON1_ADDR = const(0x9E) - - IOCAP_ADDR = const(0x391) - IOCAN_ADDR = const(0x392) - - INTCON_ADDR = const(0x0B) - OPTION_REG_ADDR = const(0x95) - - _ADCON0_CHS_POSN = const(0x02) - _ADCON0_ADON_MASK = const(0x01) - _ADCON1_ADCS_POSN = const(0x04) - _ADCON0_GO_nDONE_MASK = const(0x02) - - ADRESL_ADDR = const(0x09B) - ADRESH_ADDR = const(0x09C) - - TRISC_ADDR = const(0x08E) - - PORTA_ADDR = const(0x00C) - PORTC_ADDR = const(0x00E) - - WPUA_ADDR = const(0x20C) - - WAKE_REASON_ADDR = const(0x064C) - MEMORY_BANK_ADDR = const(0x0620) - - PCON_ADDR = const(0x096) - STATUS_ADDR = const(0x083) - - EXP_RTC_PERIOD = const(7000) - - def __init__(self, i2c=None, sda='P22', scl='P21'): - if i2c is not None: - self.i2c = i2c - else: - self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) - - self.sda = sda - self.scl = scl - self.clk_cal_factor = 1 - self.reg = bytearray(6) - self.wake_int = False - self.wake_int_pin = False - self.wake_int_pin_rising_edge = True - - # Make sure we are inserted into the - # correct board and can talk to the PIC - try: - self.read_fw_version() - except Exception as e: - raise Exception('Board not detected: {}'.format(e)) - - # init the ADC for the battery measurements - self.poke_memory(ANSELC_ADDR, 1 << 2) - self.poke_memory(ADCON0_ADDR, (0x06 << _ADCON0_CHS_POSN) | _ADCON0_ADON_MASK) - self.poke_memory(ADCON1_ADDR, (0x06 << _ADCON1_ADCS_POSN)) - # enable the pull-up on RA3 - self.poke_memory(WPUA_ADDR, (1 << 3)) - # make RC5 an input - self.set_bits_in_memory(TRISC_ADDR, 1 << 5) - # set RC6 and RC7 as outputs and enable power to the sensors and the GPS - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 6)) - self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) - - if self.read_fw_version() < 6: - raise ValueError('Firmware out of date') - - - def _write(self, data, wait=True): - self.i2c.writeto(I2C_SLAVE_ADDR, data) - if wait: - self._wait() - - def _read(self, size): - return self.i2c.readfrom(I2C_SLAVE_ADDR, size + 1)[1:(size + 1)] - - def _wait(self): - count = 0 - time.sleep_us(10) - while self.i2c.readfrom(I2C_SLAVE_ADDR, 1)[0] != 0xFF: - time.sleep_us(100) - count += 1 - if (count > 500): # timeout after 50ms - raise Exception('Board timeout') - - def _send_cmd(self, cmd): - self._write(bytes([cmd])) - - def read_hw_version(self): - self._send_cmd(CMD_HW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_fw_version(self): - self._send_cmd(CMD_FW_VER) - d = self._read(2) - return (d[1] << 8) + d[0] - - def read_product_id(self): - self._send_cmd(CMD_PROD_ID) - d = self._read(2) - return (d[1] << 8) + d[0] - - def peek_memory(self, addr): - self._write(bytes([CMD_PEEK, addr & 0xFF, (addr >> 8) & 0xFF])) - return self._read(1)[0] - - def poke_memory(self, addr, value): - self._write(bytes([CMD_POKE, addr & 0xFF, (addr >> 8) & 0xFF, value & 0xFF])) - - def magic_write_read(self, addr, _and=0xFF, _or=0, _xor=0): - self._write(bytes([CMD_MAGIC, addr & 0xFF, (addr >> 8) & 0xFF, _and & 0xFF, _or & 0xFF, _xor & 0xFF])) - return self._read(1)[0] - - def toggle_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _xor=bits) - - def mask_bits_in_memory(self, addr, mask): - self.magic_write_read(addr, _and=mask) - - def set_bits_in_memory(self, addr, bits): - self.magic_write_read(addr, _or=bits) - - def get_wake_reason(self): - """ returns the wakeup reason, a value out of constants WAKE_REASON_* """ - return self.peek_memory(WAKE_REASON_ADDR) - - def get_sleep_remaining(self): - """ returns the remaining time from sleep, as an interrupt (wakeup source) might have triggered """ - c3 = self.peek_memory(WAKE_REASON_ADDR + 3) - c2 = self.peek_memory(WAKE_REASON_ADDR + 2) - c1 = self.peek_memory(WAKE_REASON_ADDR + 1) - time_device_s = (c3 << 16) + (c2 << 8) + c1 - # this time is from PIC internal oscilator, so it needs to be adjusted with the calibration value - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_device_s / self.clk_cal_factor) + 0.5) # 0.5 used for round - return time_s - - def setup_sleep(self, time_s): - try: - self.calibrate_rtc() - except Exception: - pass - time_s = int((time_s * self.clk_cal_factor) + 0.5) # round to the nearest integer - if time_s >= 2**(8*3): - time_s = 2**(8*3)-1 - self._write(bytes([CMD_SETUP_SLEEP, time_s & 0xFF, (time_s >> 8) & 0xFF, (time_s >> 16) & 0xFF])) - - def go_to_sleep(self, gps=True): - # enable or disable back-up power to the GPS receiver - if gps: - self.set_bits_in_memory(PORTC_ADDR, 1 << 7) - else: - self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 7)) - # disable the ADC - self.poke_memory(ADCON0_ADDR, 0) - - if self.wake_int: - # Don't touch RA3, RA5 or RC1 so that interrupt wake-up works - self.poke_memory(ANSELA_ADDR, ~((1 << 3) | (1 << 5))) - self.poke_memory(ANSELC_ADDR, ~((1 << 6) | (1 << 7) | (1 << 1))) - else: - # disable power to the accelerometer, and don't touch RA3 so that button wake-up works - self.poke_memory(ANSELA_ADDR, ~(1 << 3)) - self.poke_memory(ANSELC_ADDR, ~(1 << 7)) - - self.poke_memory(ANSELB_ADDR, 0xFF) - - # check if INT pin (PIC RC1), should be used for wakeup - if self.wake_int_pin: - if self.wake_int_pin_rising_edge: - self.set_bits_in_memory(OPTION_REG_ADDR, 1 << 6) # rising edge of INT pin - else: - self.mask_bits_in_memory(OPTION_REG_ADDR, ~(1 << 6)) # falling edge of INT pin - self.mask_bits_in_memory(ANSELC_ADDR, ~(1 << 1)) # disable analog function for RC1 pin - self.set_bits_in_memory(TRISC_ADDR, 1 << 1) # make RC1 input pin - self.mask_bits_in_memory(INTCON_ADDR, ~(1 << 1)) # clear INTF - self.set_bits_in_memory(INTCON_ADDR, 1 << 4) # enable interrupt; set INTE) - - self._write(bytes([CMD_GO_SLEEP]), wait=False) - # kill the run pin - Pin('P3', mode=Pin.OUT, value=0) - - def calibrate_rtc(self): - # the 1.024 factor is because the PIC LF operates at 31 KHz - # WDT has a frequency divider to generate 1 ms - # and then there is a binary prescaler, e.g., 1, 2, 4 ... 512, 1024 ms - # hence the need for the constant - self._write(bytes([CMD_CALIBRATE]), wait=False) - self.i2c.deinit() - Pin('P21', mode=Pin.IN) - pulses = pycom.pulses_get('P21', 100) - self.i2c.init(mode=I2C.MASTER, pins=(self.sda, self.scl)) - idx = 0 - for i in range(len(pulses)): - if pulses[i][1] > EXP_RTC_PERIOD: - idx = i - break - try: - period = pulses[idx][1] - pulses[(idx - 1)][1] - except: - period = 0 - if period > 0: - self.clk_cal_factor = (EXP_RTC_PERIOD / period) * (1000 / 1024) - if self.clk_cal_factor > 1.25 or self.clk_cal_factor < 0.75: - self.clk_cal_factor = 1 - - def button_pressed(self): - button = self.peek_memory(PORTA_ADDR) & (1 << 3) - return not button - - def read_battery_voltage(self): - self.set_bits_in_memory(ADCON0_ADDR, _ADCON0_GO_nDONE_MASK) - time.sleep_us(50) - while self.peek_memory(ADCON0_ADDR) & _ADCON0_GO_nDONE_MASK: - time.sleep_us(100) - adc_val = (self.peek_memory(ADRESH_ADDR) << 2) + (self.peek_memory(ADRESL_ADDR) >> 6) - return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET - - def setup_int_wake_up(self, rising, falling): - """ rising is for activity detection, falling for inactivity """ - wake_int = False - if rising: - self.set_bits_in_memory(IOCAP_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAP_ADDR, ~(1 << 5)) - - if falling: - self.set_bits_in_memory(IOCAN_ADDR, 1 << 5) - wake_int = True - else: - self.mask_bits_in_memory(IOCAN_ADDR, ~(1 << 5)) - self.wake_int = wake_int - - def setup_int_pin_wake_up(self, rising_edge = True): - """ allows wakeup to be made by the INT pin (PIC -RC1) """ - self.wake_int_pin = True - self.wake_int_pin_rising_edge = rising_edge diff --git a/pybytes/pytrack/lib/pytrack.py b/pybytes/pytrack/lib/pytrack.py deleted file mode 100644 index 3e4d39b..0000000 --- a/pybytes/pytrack/lib/pytrack.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -from pycoproc import Pycoproc - -__version__ = '1.4.0' - -class Pytrack(Pycoproc): - - def __init__(self, i2c=None, sda='P22', scl='P21'): - Pycoproc.__init__(self, i2c, sda, scl) diff --git a/pybytes/README.md b/shields/README.md similarity index 100% rename from pybytes/README.md rename to shields/README.md diff --git a/pybytes/pyscan/main.py b/shields/pyscan_1_pybytes.py similarity index 100% rename from pybytes/pyscan/main.py rename to shields/pyscan_1_pybytes.py diff --git a/pybytes/pysense/main.py b/shields/pysense_1_pybytes.py similarity index 100% rename from pybytes/pysense/main.py rename to shields/pysense_1_pybytes.py diff --git a/pybytes/pytrack/main.py b/shields/pytrack_1_pybytes.py similarity index 100% rename from pybytes/pytrack/main.py rename to shields/pytrack_1_pybytes.py From dcb5292283f3e1dd866f04bbc6ef740bd2f5db32 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 13:27:03 +0100 Subject: [PATCH 21/39] pybytes shield fixes --- shields/pyscan_1_pybytes.py | 14 +++++++------- shields/pysense_1_pybytes.py | 28 ++++++++++++++++++++++------ shields/pytrack_1_pybytes.py | 6 +++--- 3 files changed, 32 insertions(+), 16 deletions(-) diff --git a/shields/pyscan_1_pybytes.py b/shields/pyscan_1_pybytes.py index 26a58e9..458b743 100644 --- a/shields/pyscan_1_pybytes.py +++ b/shields/pyscan_1_pybytes.py @@ -19,7 +19,7 @@ DEBUG = False # change to True to see debug messages -from pyscan import Pyscan +from pycoproc_1 import Pycoproc from MFRC630 import MFRC630 from LIS2HH12 import LIS2HH12 from LTR329ALS01 import LTR329ALS01 @@ -31,7 +31,7 @@ VALID_CARDS = [[0x43, 0x95, 0xDD, 0xF8], [0x43, 0x95, 0xDD, 0xF9]] -py = Pyscan() +py = Pycoproc(Pycoproc.PYSENSE) nfc = MFRC630(py) lt = LTR329ALS01(py) li = LIS2HH12(py) @@ -57,8 +57,8 @@ def print_debug(msg): def send_sensor_data(name, timeout): while(pybytes): - pybytes.send_virtual_pin_value(True, 2, lt.light()) - pybytes.send_virtual_pin_value(True, 3, li.acceleration()) + pybytes.send_signal(2, lt.light()) + pybytes.send_signal(3, li.acceleration()) time.sleep(timeout) def discovery_loop(arg1, arg2): @@ -78,16 +78,16 @@ def discovery_loop(arg1, arg2): if (check_uid(list(uid), uid_len)) > 0: print_debug('Card is listed, turn LED green') pycom.rgbled(RGB_GREEN) - pybytes.send_virtual_pin_value(True, 1, ('Card is listed, Access granted', uid)) + pybytes.send_signal(1, ('Card is listed, Access granted', uid)) else: print_debug('Card is not listed, turn LED red') pycom.rgbled(RGB_RED) - pybytes.send_virtual_pin_value(True, 1, ('Card is not listed, Access denied', uid)) + pybytes.send_signal(1, ('Card is not listed, Access denied', uid)) else: # No card detected print_debug('Did not detect any card...') pycom.rgbled(RGB_BLUE) - pybytes.send_virtual_pin_value(True, 1, ('Did not detect any card', 0)) + pybytes.send_signal(1, ('Did not detect any card', 0)) nfc.mfrc630_cmd_reset() time.sleep(5) nfc.mfrc630_cmd_init() diff --git a/shields/pysense_1_pybytes.py b/shields/pysense_1_pybytes.py index babb9c3..2d3326d 100644 --- a/shields/pysense_1_pybytes.py +++ b/shields/pysense_1_pybytes.py @@ -10,13 +10,13 @@ # See https://docs.pycom.io for more information regarding library specifics -from pysense import Pysense +from pycoproc_1 import Pycoproc from LIS2HH12 import LIS2HH12 from SI7006A20 import SI7006A20 from LTR329ALS01 import LTR329ALS01 from MPL3115A2 import MPL3115A2,ALTITUDE,PRESSURE -py = Pysense() +py = Pycoproc(Pycoproc.PYSENSE) mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals si = SI7006A20(py) lt = LTR329ALS01(py) @@ -27,10 +27,26 @@ import uos def send_sensor_data(): + h2 = None + t2 = None + l2 = None while (pybytes): - pybytes.send_virtual_pin_value(True, 1, si.humidity()) - pybytes.send_virtual_pin_value(True, 2, si.temperature()) - pybytes.send_virtual_pin_value(True, 3, lt.light()) + h = round(si.humidity(),1) + t = round(si.temperature(),1) + l = lt.light() + if h != h2: + print('humidity', h) + pybytes.send_signal(1, h) + h2=h + if t != t2: + print('temperature', t) + pybytes.send_signal(2, t) + t2=t + if l != l2: + print('luminocity', l) + pybytes.send_signal(3, l) + l2=l sleep(10) -_thread.start_new_thread(send_sensor_data, ()) +# _thread.start_new_thread(send_sensor_data, ()) +send_sensor_data() diff --git a/shields/pytrack_1_pybytes.py b/shields/pytrack_1_pybytes.py index 81bd2ac..51e03ab 100644 --- a/shields/pytrack_1_pybytes.py +++ b/shields/pytrack_1_pybytes.py @@ -18,7 +18,7 @@ from machine import SD from machine import Timer from L76GNSS import L76GNSS -from pytrack import Pytrack +from pycoproc_1 import Pycoproc from LIS2HH12 import LIS2HH12 # setup as a station @@ -34,7 +34,7 @@ print('\nRTC Set from NTP to UTC:', rtc.now()) utime.timezone(7200) print('Adjusted from UTC to EST timezone', utime.localtime(), '\n') -py = Pytrack() +py = Pycoproc(Pycoproc.PYTRACK) l76 = L76GNSS(py, timeout=30) chrono = Timer.Chrono() chrono.start() @@ -45,7 +45,7 @@ while (pybytes): coord = l76.coordinates() #f.write("{} - {}\n".format(coord, rtc.now())) - print('Sending data') + print('Sending data', coord) pybytes.send_signal(1, coord) pybytes.send_signal(2, li.acceleration()) time.sleep(10) From 7628995489ef54b8f81964a316b32d800b88a20d Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 13:32:20 +0100 Subject: [PATCH 22/39] readme --- shields/README.md | 22 ++++++---------------- shields/shield_2.py | 3 ++- 2 files changed, 8 insertions(+), 17 deletions(-) diff --git a/shields/README.md b/shields/README.md index 406b228..e8ecf84 100644 --- a/shields/README.md +++ b/shields/README.md @@ -1,23 +1,13 @@

-# Pybytes Examples +# Pytrack, Pysense and Pyscan libraries -Please note that these examples only work when using the `pybytes` firmware. +## Introduction +This directory contains libraries and out of the box examples for Pysense, Pytrack, and Pyscan, both versions 1 and 2.0x of these shields. -# Pytrack, Pysense, Pyscan -- To run pytrack on individuals module you will need to create one pybytes_config.json file on root which usually contains data related to device e.g Network preferance, device id, server, username, password etc. - -- You will needs to upload all the files to module in order to get data on pybytes dashboard. +1. Upload all the files to your module +2. Open Pymakr +3. Run an example that matches to your shield Note: Note: For using Pyscan, you need to upload either MFRC630.mpy or MFRC630.py. It is always recommended to use MFRC630.mpy as it takes less space on your module. - -- Pytrack: -GPS coordinate and Acceleration would give result in tuples. - -- Pysense: -Humidity and temperature output would be in float32. -Light sensor output would be in tuples. - -- Pyscan: -Light sensor and Acceleration would give output in tuples. diff --git a/shields/shield_2.py b/shields/shield_2.py index 6fd28cb..8fb74e0 100644 --- a/shields/shield_2.py +++ b/shields/shield_2.py @@ -8,7 +8,8 @@ # available at https://www.pycom.io/opensource/licensing # -# This script demonstrates two examples: +# This script support Pysense 2 and Pytrack 2 +# It demonstrates two examples: # * go to ultra low power mode (~10uA @3.75V) with all sensors, incl accelerometer and also pycom module (Fipy, Gpy, etc) off - tap the MCLR button for this # * go to low power mode (~165uA @3.75V) with accelerometer on, pycom module in deepsleep and wake from accelerometer interrupt - hold the MCLR button down for this From 3693deb8b6edda1de6a6a949071e4844f8604456 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Tue, 2 Mar 2021 17:37:44 +0100 Subject: [PATCH 23/39] revert gps_standby() otherwise the GPS chip is (almost never) reachable over i2c --- shields/lib/pycoproc_2.py | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/shields/lib/pycoproc_2.py b/shields/lib/pycoproc_2.py index 94cff44..b563d3b 100644 --- a/shields/lib/pycoproc_2.py +++ b/shields/lib/pycoproc_2.py @@ -340,14 +340,21 @@ def read_battery_voltage(self): return (((adc_val * 3.3 * 280) / 1023) / 180) + 0.01 # add 10mV to compensate for the drop in the FET def gps_standby(self, enabled=True): - # make RC4 an output - self.write_bit(TRISC_ADDR, 4, 0) if enabled: - # drive RC4 low - self.write_bit(LATC_ADDR, 4, 0) + # make RC4 input + self.set_bits_in_memory(TRISC_ADDR, 1 << 4) else: + # make RC4 an output + self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 4)) + # drive RC4 high + self.set_bits_in_memory(PORTC_ADDR, 1 << 4) + time.sleep(0.2) + # drive RC4 low + self.mask_bits_in_memory(PORTC_ADDR, ~(1 << 4)) + time.sleep(0.2) # drive RC4 high - self.write_bit(LATC_ADDR, 4, 1) + self.set_bits_in_memory(PORTC_ADDR, 1 << 4) + time.sleep(0.2) def sensor_power(self, enabled=True): # make RC7 an output From cf24f160a3d359feb1b5c8c6cfa7abf645fe5e8e Mon Sep 17 00:00:00 2001 From: peter-pycom <61411318+peter-pycom@users.noreply.github.com> Date: Thu, 11 Mar 2021 14:49:57 +0100 Subject: [PATCH 24/39] Typo (#138) --- shields/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shields/README.md b/shields/README.md index e8ecf84..0586192 100644 --- a/shields/README.md +++ b/shields/README.md @@ -9,5 +9,5 @@ This directory contains libraries and out of the box examples for Pysense, Pytra 2. Open Pymakr 3. Run an example that matches to your shield -Note: Note: For using Pyscan, you need to upload either MFRC630.mpy or MFRC630.py. +Note: For using Pyscan, you need to upload either MFRC630.mpy or MFRC630.py. It is always recommended to use MFRC630.mpy as it takes less space on your module. From 5ef70f957d780c5ee40eed562061219faef25088 Mon Sep 17 00:00:00 2001 From: peter-pycom <61411318+peter-pycom@users.noreply.github.com> Date: Thu, 11 Mar 2021 16:11:37 +0100 Subject: [PATCH 25/39] cleanup old pysense stuff (#137) --- README.md | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/README.md b/README.md index 178f449..ce4e46c 100644 --- a/README.md +++ b/README.md @@ -3,19 +3,12 @@ # Pycom Libraries and Examples ## Introduction -This repository contains out of the box examples for Pycom devices, including Pysense, Pytrack, and Pyscan. +This repository contains libraries and out of the box examples for Pycom devices, including the Shields: Pysense, Pytrack, and Pyscan. ## Table of Contents * [Examples](/examples) * [Libraries](/lib) -* [Pysense](/pysense) -* [Pytrack](/pytrack) -* [Pyscan](/pyscan) -* [Pybytes](/pybytes) - -## Pysense, Pytrack, Pyscan - -To install the required libraries for Pysense, Pytrack, and Pyscan, please download this repo as a ZIP file. You will then be able to extract and upload the library files to your Pycom device (via FTP or Pymakr Plugin). Please see [docs.pycom.io](https://docs.pycom.io) for more information. +* [Shields](/shields) ## Links * [Pycom](https://pycom.io) From e6985cd53d8647cd7a26ddacc79ac85b67754a58 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Thu, 11 Mar 2021 16:58:39 +0100 Subject: [PATCH 26/39] mv MFRC630 --- {lib/MFRC630 => shields/lib}/MFRC630.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename {lib/MFRC630 => shields/lib}/MFRC630.py (100%) diff --git a/lib/MFRC630/MFRC630.py b/shields/lib/MFRC630.py similarity index 100% rename from lib/MFRC630/MFRC630.py rename to shields/lib/MFRC630.py From 29c580d0159bc9ed08c9785c66261567b0796eb0 Mon Sep 17 00:00:00 2001 From: peter-pycom <61411318+peter-pycom@users.noreply.github.com> Date: Fri, 9 Apr 2021 15:21:01 +0200 Subject: [PATCH 27/39] Errors (#142) Added & updated error messages when using incompatible shield (firmware) --- shields/lib/pycoproc_1.py | 2 +- shields/lib/pycoproc_2.py | 2 +- shields/pysense_2.py | 2 ++ shields/pytrack_2.py | 2 ++ 4 files changed, 6 insertions(+), 2 deletions(-) diff --git a/shields/lib/pycoproc_1.py b/shields/lib/pycoproc_1.py index 48fa051..a8f7e82 100644 --- a/shields/lib/pycoproc_1.py +++ b/shields/lib/pycoproc_1.py @@ -127,7 +127,7 @@ def __init__(self, board_type, i2c=None, sda='P22', scl='P21'): self.mask_bits_in_memory(TRISC_ADDR, ~(1 << 7)) if self.read_fw_version() < 6: - raise ValueError('Firmware out of date') + raise ValueError('Firmware for Shield1 out of date') def _write(self, data, wait=True): diff --git a/shields/lib/pycoproc_2.py b/shields/lib/pycoproc_2.py index b563d3b..a1ead51 100644 --- a/shields/lib/pycoproc_2.py +++ b/shields/lib/pycoproc_2.py @@ -152,7 +152,7 @@ def __init__(self, i2c=None, sda='P22', scl='P21'): # for Pysense/Pytrack 2.0, the minimum firmware version is 15 fw = self.read_fw_version() if fw < 16: - raise ValueError('Firmware out of date', fw) + raise ValueError('Firmware for Shield2 out of date', fw) # init the ADC for the battery measurements self.write_byte(ANSELC_ADDR, 1 << 2) # RC2 analog input diff --git a/shields/pysense_2.py b/shields/pysense_2.py index cfa6280..c7e1697 100644 --- a/shields/pysense_2.py +++ b/shields/pysense_2.py @@ -24,6 +24,8 @@ pycom.rgbled(0x0A0A08) # white py = Pycoproc() +if py.read_product_id() != Pycoproc.USB_PID_PYSENSE: + raise Exception('Not a Pysense') mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals print("MPL3115A2 temperature: " + str(mp.temperature())) diff --git a/shields/pytrack_2.py b/shields/pytrack_2.py index 3f33ff5..8627e22 100644 --- a/shields/pytrack_2.py +++ b/shields/pytrack_2.py @@ -36,6 +36,8 @@ print('Adjusted from UTC to EST timezone', utime.localtime(), '\n') py = Pycoproc() +if py.read_product_id() != Pycoproc.USB_PID_PYTRACK: + raise Exception('Not a Pytrack') time.sleep(1) l76 = L76GNSS(py, timeout=30, buffer=512) From f4845e654c3be6f8b407ba161d1b78d733b2daa5 Mon Sep 17 00:00:00 2001 From: Lukanite Date: Mon, 12 Apr 2021 07:03:16 -0400 Subject: [PATCH 28/39] Ensure checksum is 2 digits (#143) Fix bug where some L76 messages are ignored due to the checksum being one digit long (i.e. 'F') vs. the expected 2 digit length ('0F') --- shields/lib/L76GNSS.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shields/lib/L76GNSS.py b/shields/lib/L76GNSS.py index 37cc2fd..c493eb1 100644 --- a/shields/lib/L76GNSS.py +++ b/shields/lib/L76GNSS.py @@ -113,7 +113,7 @@ def _checksum(self, nmeadata): calc_cksum = 0 for s in nmeadata: calc_cksum ^= ord(s) - return('{:X}'.format(calc_cksum)) + return('{:02X}'.format(calc_cksum)) def write(self, data): self.i2c.writeto(GPS_I2CADDR, '${}*{}\r\n'.format(data, self._checksum(data)) ) From f24b3fbbbfeb3a681cb92e049db9e25db2a6e7c6 Mon Sep 17 00:00:00 2001 From: gijsio <67470426+gijsio@users.noreply.github.com> Date: Mon, 12 Apr 2021 15:37:56 +0200 Subject: [PATCH 29/39] makefile release (#141) --- .gitignore | 12 ++++ Makefile | 102 ++++++++++++++++++++++++++++ shields/pyscan_1.py | 126 +++++++++++++++++++++-------------- shields/pyscan_1_nfc.py | 75 --------------------- shields/pyscan_1_pybytes.py | 98 --------------------------- shields/pysense_1.py | 23 ++++++- shields/pysense_1_pybytes.py | 52 --------------- shields/pysense_2.py | 20 ++++++ shields/pytrack_1.py | 16 +++++ shields/pytrack_1_pybytes.py | 51 -------------- shields/pytrack_2.py | 12 +++- 11 files changed, 257 insertions(+), 330 deletions(-) create mode 100644 Makefile delete mode 100644 shields/pyscan_1_nfc.py delete mode 100644 shields/pyscan_1_pybytes.py delete mode 100644 shields/pysense_1_pybytes.py delete mode 100644 shields/pytrack_1_pybytes.py diff --git a/.gitignore b/.gitignore index beced4e..e943765 100644 --- a/.gitignore +++ b/.gitignore @@ -5,3 +5,15 @@ *.conf .DS_Store +pyscan/* +pysense/* +pysense2/* +pytrack/* +pytrack2/* + +pyscan.zip +pysense.zip +pysense2.zip +pytrack.zip +pytrack2.zip + diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..17034ef --- /dev/null +++ b/Makefile @@ -0,0 +1,102 @@ +release: pyscan pysense pysense2 pytrack pytrack2 + + +pyscan: + rm -rf pyscan + rm -f pyscan.zip + @echo "Making Pyscan" + mkdir pyscan + mkdir pyscan/lib + #sensors + cp shields/lib/LIS2HH12.py pyscan/lib/ + cp shields/lib/MFRC630.py pyscan/lib/ + cp shields/lib/SI7006A20.py pyscan/lib/ + cp shields/lib/LTR329ALS01.py pyscan/lib/ + #pycoproc + cp shields/lib/pycoproc_1.py pyscan/lib/ + #example + cp shields/pyscan_1.py pyscan/main.py + + zip -r pyscan.zip pyscan + +pysense: + rm -rf pysense + rm -f pysense.zip + @echo "Making Pysense" + mkdir pysense + mkdir pysense/lib + # sensors + cp shields/lib/LIS2HH12.py pysense/lib/ + cp shields/lib/LTR329ALS01.py pysense/lib/ + cp shields/lib/MPL3115A2.py pysense/lib/ + cp shields/lib/SI7006A20.py pysense/lib/ + # pycoproc + cp shields/lib/pycoproc_1.py pysense/lib/ + # example + cp shields/pysense_1.py pysense/main.py + + zip -r pysense.zip pysense + +pysense2: + rm -rf pysense2 + rm -f pysense2.zip + @echo "Making Pysense 2" + mkdir pysense2 + mkdir pysense2/lib + # sensors + cp shields/lib/LIS2HH12.py pysense2/lib/ + cp shields/lib/LTR329ALS01.py pysense2/lib/ + cp shields/lib/MPL3115A2.py pysense2/lib/ + cp shields/lib/SI7006A20.py pysense2/lib/ + # pycoproc + cp shields/lib/pycoproc_2.py pysense2/lib/ + # example + cp shields/pysense_2.py pysense2/main.py + + zip -r pysense2.zip pysense2 + +pytrack: + rm -rf pytrack + rm -f pytrack.zip + @echo "Making Pytrack" + mkdir pytrack + mkdir pytrack/lib + #sensors + cp shields/lib/L76GNSS.py pytrack/lib/ + cp shields/lib/LIS2HH12.py pytrack/lib/ + #pycoproc + cp shields/lib/pycoproc_1.py pytrack/lib/ + #example + cp shields/pytrack_1.py pytrack/main.py + + zip -r pytrack.zip pytrack + +pytrack2: + rm -rf pytrack2 + rm -f pytrack2.zip + @echo "Making Pytrack2" + mkdir pytrack2 + mkdir pytrack2/lib + #sensors + cp shields/lib/L76GNSS.py pytrack2/lib/ + cp shields/lib/LIS2HH12.py pytrack2/lib/ + #pycoproc + cp shields/lib/pycoproc_2.py pytrack2/lib/ + #example + cp shields/pytrack_2.py pytrack2/main.py + + zip -r pytrack2.zip pytrack2 + +clean: + @echo "Cleaning up files" + rm -rf pyscan + rm -rf pysense + rm -rf pysense2 + rm -rf pytrack + rm -rf pytrack2 + + rm -f pyscan.zip + rm -f pysense.zip + rm -f pysense2.zip + rm -f pytrack.zip + rm -f pytrack2.zip \ No newline at end of file diff --git a/shields/pyscan_1.py b/shields/pyscan_1.py index 66ab94e..9e9c263 100644 --- a/shields/pyscan_1.py +++ b/shields/pyscan_1.py @@ -1,86 +1,114 @@ ''' Simple Pyscan NFC / MiFare Classic Example -Copyright (c) 2020, Pycom Limited. +Copyright (c) 2019, Pycom Limited. -This example runs the NFC discovery loop in a thread. -If a card is detected it will read the UID and compare it to VALID_CARDS -RGB LED is BLUE while waiting for card, -GREEN if card is valid, RED if card is invalid +This example continuously sends a REQA for ISO14443A card type +If a card is discovered, it will read the UID +If DECODE_CARD = True, will attempt to authenticate with CARDkey +If authentication succeeds will attempt to read sectors from the card ''' -DEBUG = False # change to True to see debug messages - from pycoproc_1 import Pycoproc from MFRC630 import MFRC630 from LIS2HH12 import LIS2HH12 from LTR329ALS01 import LTR329ALS01 -import binascii import time import pycom -import _thread +#add your card UID here VALID_CARDS = [[0x43, 0x95, 0xDD, 0xF8], [0x43, 0x95, 0xDD, 0xF9], [0x46, 0x5A, 0xEB, 0x7D, 0x8A, 0x08, 0x04]] + +# This is the default key for an unencrypted MiFare card +CARDkey = [ 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF ] +DECODE_CARD = False + py = Pycoproc(Pycoproc.PYSCAN) nfc = MFRC630(py) lt = LTR329ALS01(py) li = LIS2HH12(py) +pybytes_enabled = False +if 'pybytes' in globals(): + if(pybytes.isconnected()): + print('Pybytes is connected, sending signals to Pybytes') + pybytes_enabled = True + RGB_BRIGHTNESS = 0x8 RGB_RED = (RGB_BRIGHTNESS << 16) RGB_GREEN = (RGB_BRIGHTNESS << 8) RGB_BLUE = (RGB_BRIGHTNESS) +counter = 0 + +def check_uid(uid, len): + return VALID_CARDS.count(uid[:len]) + +def send_sensor_data(name, timeout): + if(pybytes_enabled): + while(True): + pybytes.send_signal(2, lt.light()) + pybytes.send_signal(3, li.acceleration()) + time.sleep(timeout) + # Make sure heartbeat is disabled before setting RGB LED pycom.heartbeat(False) # Initialise the MFRC630 with some settings nfc.mfrc630_cmd_init() -def check_uid(uid, len): - return VALID_CARDS.count(uid[:len]) - -def print_debug(msg): - if DEBUG: - print(msg) - -def send_sensor_data(name, timeout): - while(True): - print(lt.light()) - print(li.acceleration()) - time.sleep(timeout) - -def discovery_loop(nfc, id): - while True: - # Send REQA for ISO14443A card type - print_debug('Sending REQA for ISO14443A card type...') - atqa = nfc.mfrc630_iso14443a_WUPA_REQA(nfc.MFRC630_ISO14443_CMD_REQA) - print_debug('Response: {}'.format(atqa)) - if (atqa != 0): - # A card has been detected, read UID - print_debug('A card has been detected, read UID...') - uid = bytearray(10) - uid_len = nfc.mfrc630_iso14443a_select(uid) - print_debug('UID has length: {}'.format(uid_len)) - if (uid_len > 0): - print_debug('Checking if card with UID: [{:s}] is listed in VALID_CARDS...'.format(binascii.hexlify(uid[:uid_len],' ').upper())) +print('Scanning for cards') +while True: + # Send REQA for ISO14443A card type + atqa = nfc.mfrc630_iso14443a_WUPA_REQA(nfc.MFRC630_ISO14443_CMD_REQA) + if (atqa != 0): + # A card has been detected, read UID + print('A card has been detected, reading its UID ...') + uid = bytearray(10) + uid_len = nfc.mfrc630_iso14443a_select(uid) + print('UID has length {}'.format(uid_len)) + if (uid_len > 0): + # A valid UID has been detected, print details + counter += 1 + print("%d\tUID [%d]: %s" % (counter, uid_len, nfc.format_block(uid, uid_len))) + if DECODE_CARD: + # Try to authenticate with CARD key + nfc.mfrc630_cmd_load_key(CARDkey) + for sector in range(0, 16): + if (nfc.mfrc630_MF_auth(uid, nfc.MFRC630_MF_AUTH_KEY_A, sector * 4)): + pycom.rgbled(RGB_GREEN) + # Authentication was sucessful, read card data + readbuf = bytearray(16) + for b in range(0, 4): + f_sect = sector * 4 + b + len = nfc.mfrc630_MF_read_block(f_sect, readbuf) + print("\t\tSector %s: Block: %s: %s" % (nfc.format_block([sector], 1), nfc.format_block([b], 1), nfc.format_block(readbuf, len))) + else: + print("Authentication denied for sector %s!" % nfc.format_block([sector], 1)) + pycom.rgbled(RGB_RED) + # It is necessary to call mfrc630_MF_deauth after authentication + # Although this is also handled by the reset / init cycle + nfc.mfrc630_MF_deauth() + else: + #check if card uid is listed in VALID_CARDS if (check_uid(list(uid), uid_len)) > 0: - print_debug('Card is listed, turn LED green') + print('Card is listed, turn LED green') pycom.rgbled(RGB_GREEN) + if(pybytes_enabled): + pybytes.send_signal(1, ('Card is listed', uid)) else: - print_debug('Card is not listed, turn LED red') + print('Card is not listed, turn LED red') pycom.rgbled(RGB_RED) - else: - # No card detected - print_debug('Did not detect any card...') - pycom.rgbled(RGB_BLUE) - nfc.mfrc630_cmd_reset() - time.sleep(.5) - nfc.mfrc630_cmd_init() - -# This is the start of our main execution... start the thread -_thread.start_new_thread(discovery_loop, (nfc, 0)) -_thread.start_new_thread(send_sensor_data, ('Thread 2', 10)) + if(pybytes_enabled): + pybytes.send_signal(1, ('Unauthorized card detected', uid)) + + else: + pycom.rgbled(RGB_BLUE) + # We could go into power saving mode here... to be investigated + nfc.mfrc630_cmd_reset() + time.sleep(.5) + # Re-Initialise the MFRC630 with settings as these got wiped during reset + nfc.mfrc630_cmd_init() diff --git a/shields/pyscan_1_nfc.py b/shields/pyscan_1_nfc.py deleted file mode 100644 index 6b2ea36..0000000 --- a/shields/pyscan_1_nfc.py +++ /dev/null @@ -1,75 +0,0 @@ -''' -Simple Pyscan NFC / MiFare Classic Example -Copyright (c) 2019, Pycom Limited. - -This example continuously sends a REQA for ISO14443A card type -If a card is discovered, it will read the UID -If DECODE_CARD = True, will attempt to authenticate with CARDkey -If authentication succeeds will attempt to read sectors from the card -''' - -from pycoproc_1 import Pycoproc -from MFRC630 import MFRC630 -import time -import pycom - -# This is the default key for an unencrypted MiFare card -CARDkey = [ 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF ] -DECODE_CARD = False - -py = Pycoproc(Pycoproc.PYSCAN) -nfc = MFRC630(py) - -RGB_BRIGHTNESS = 0x8 - -RGB_RED = (RGB_BRIGHTNESS << 16) -RGB_GREEN = (RGB_BRIGHTNESS << 8) -RGB_BLUE = (RGB_BRIGHTNESS) - -counter = 0 - -# Make sure heartbeat is disabled before setting RGB LED -pycom.heartbeat(False) - -# Initialise the MFRC630 with some settings -nfc.mfrc630_cmd_init() - -while True: - # Send REQA for ISO14443A card type - atqa = nfc.mfrc630_iso14443a_WUPA_REQA(nfc.MFRC630_ISO14443_CMD_REQA) - if (atqa != 0): - # A card has been detected, read UID - uid = bytearray(10) - uid_len = nfc.mfrc630_iso14443a_select(uid) - if (uid_len > 0): - # A valid UID has been detected, print details - counter += 1 - print("%d\tUID [%d]: %s" % (counter, uid_len, nfc.format_block(uid, uid_len))) - if DECODE_CARD: - # Try to authenticate with CARD key - nfc.mfrc630_cmd_load_key(CARDkey) - for sector in range(0, 16): - if (nfc.mfrc630_MF_auth(uid, nfc.MFRC630_MF_AUTH_KEY_A, sector * 4)): - pycom.rgbled(RGB_GREEN) - # Authentication was sucessful, read card data - readbuf = bytearray(16) - for b in range(0, 4): - f_sect = sector * 4 + b - len = nfc.mfrc630_MF_read_block(f_sect, readbuf) - print("\t\tSector %s: Block: %s: %s" % (nfc.format_block([sector], 1), nfc.format_block([b], 1), nfc.format_block(readbuf, len))) - else: - print("Authentication denied for sector %s!" % nfc.format_block([sector], 1)) - pycom.rgbled(RGB_RED) - # It is necessary to call mfrc630_MF_deauth after authentication - # Although this is also handled by the reset / init cycle - nfc.mfrc630_MF_deauth() - else: - # If we're not trying to authenticate, show green when a UID > 0 has been detected - pycom.rgbled(RGB_GREEN) - else: - pycom.rgbled(RGB_BLUE) - # We could go into power saving mode here... to be investigated - nfc.mfrc630_cmd_reset() - time.sleep(.5) - # Re-Initialise the MFRC630 with settings as these got wiped during reset - nfc.mfrc630_cmd_init() diff --git a/shields/pyscan_1_pybytes.py b/shields/pyscan_1_pybytes.py deleted file mode 100644 index 458b743..0000000 --- a/shields/pyscan_1_pybytes.py +++ /dev/null @@ -1,98 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -''' -Simple Pyscan NFC / MiFare Classic Example -Copyright (c) 2019, Pycom Limited. -This example runs the NFC discovery loop in a thread. -If a card is detected it will read the UID and compare it to VALID_CARDS -RGB LED is BLUE while waiting for card, -GREEN if card is valid, RED if card is invalid -''' - -DEBUG = False # change to True to see debug messages - -from pycoproc_1 import Pycoproc -from MFRC630 import MFRC630 -from LIS2HH12 import LIS2HH12 -from LTR329ALS01 import LTR329ALS01 -import binascii -import time -import pycom -import _thread - -VALID_CARDS = [[0x43, 0x95, 0xDD, 0xF8], - [0x43, 0x95, 0xDD, 0xF9]] - -py = Pycoproc(Pycoproc.PYSENSE) -nfc = MFRC630(py) -lt = LTR329ALS01(py) -li = LIS2HH12(py) - -RGB_BRIGHTNESS = 0x8 - -RGB_RED = (RGB_BRIGHTNESS << 16) -RGB_GREEN = (RGB_BRIGHTNESS << 8) -RGB_BLUE = (RGB_BRIGHTNESS) - -# Make sure heartbeat is disabled before setting RGB LED -pycom.heartbeat(False) - -# Initialise the MFRC630 with some settings -nfc.mfrc630_cmd_init() - -def check_uid(uid, len): - return VALID_CARDS.count(uid[:len]) - -def print_debug(msg): - if DEBUG: - print(msg) - -def send_sensor_data(name, timeout): - while(pybytes): - pybytes.send_signal(2, lt.light()) - pybytes.send_signal(3, li.acceleration()) - time.sleep(timeout) - -def discovery_loop(arg1, arg2): - while(pybytes): - # Send REQA for ISO14443A card type - print_debug('Sending REQA for ISO14443A card type...') - atqa = nfc.mfrc630_iso14443a_WUPA_REQA(nfc.MFRC630_ISO14443_CMD_REQA) - print_debug('Response: {}'.format(atqa)) - if (atqa != 0): - # A card has been detected, read UID - print_debug('A card has been detected, read UID...') - uid = bytearray(10) - uid_len = nfc.mfrc630_iso14443a_select(uid) - print_debug('UID has length: {}'.format(uid_len)) - if (uid_len > 0): - print_debug('Checking if card with UID: [{:s}] is listed in VALID_CARDS...'.format(binascii.hexlify(uid[:uid_len],' ').upper())) - if (check_uid(list(uid), uid_len)) > 0: - print_debug('Card is listed, turn LED green') - pycom.rgbled(RGB_GREEN) - pybytes.send_signal(1, ('Card is listed, Access granted', uid)) - else: - print_debug('Card is not listed, turn LED red') - pycom.rgbled(RGB_RED) - pybytes.send_signal(1, ('Card is not listed, Access denied', uid)) - else: - # No card detected - print_debug('Did not detect any card...') - pycom.rgbled(RGB_BLUE) - pybytes.send_signal(1, ('Did not detect any card', 0)) - nfc.mfrc630_cmd_reset() - time.sleep(5) - nfc.mfrc630_cmd_init() - - -# This is the start of our main execution... start the thread -_thread.start_new_thread(discovery_loop, (nfc, 0)) -_thread.start_new_thread(send_sensor_data, ('Thread 2',10)) diff --git a/shields/pysense_1.py b/shields/pysense_1.py index 0a0d4b1..2a4e126 100644 --- a/shields/pysense_1.py +++ b/shields/pysense_1.py @@ -25,13 +25,18 @@ py = Pycoproc(Pycoproc.PYSENSE) +pybytes_enabled = False +if 'pybytes' in globals(): + if(pybytes.isconnected()): + print('Pybytes is connected, sending signals to Pybytes') + pybytes_enabled = True + mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals print("MPL3115A2 temperature: " + str(mp.temperature())) print("Altitude: " + str(mp.altitude())) mpp = MPL3115A2(py,mode=PRESSURE) # Returns pressure in Pa. Mode may also be set to ALTITUDE, returning a value in meters print("Pressure: " + str(mpp.pressure())) - si = SI7006A20(py) print("Temperature: " + str(si.temperature())+ " deg C and Relative Humidity: " + str(si.humidity()) + " %RH") print("Dew point: "+ str(si.dew_point()) + " deg C") @@ -47,8 +52,20 @@ print("Roll: " + str(li.roll())) print("Pitch: " + str(li.pitch())) -print("Battery voltage: " + str(py.read_battery_voltage())) +# set your battery voltage limits here +vmax = 4.2 +vmin = 3.3 +battery_voltage = py.read_battery_voltage() +battery_percentage = (battery_voltage - vmin / (vmax - vmin))*100 +print("Battery voltage: " + str(py.read_battery_voltage()), " percentage: ", battery_percentage) +if(pybytes_enabled): + pybytes.send_signal(1, mpp.pressure()) + pybytes.send_signal(2, si.temperature()) + pybytes.send_signal(3, lt.light()) + pybytes.send_signal(4, li.acceleration()) + pybytes.send_battery_level(int(battery_percentage)) + print("Sent data to pybytes") -time.sleep(3) +time.sleep(5) py.setup_sleep(10) py.go_to_sleep() diff --git a/shields/pysense_1_pybytes.py b/shields/pysense_1_pybytes.py deleted file mode 100644 index 2d3326d..0000000 --- a/shields/pysense_1_pybytes.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -# See https://docs.pycom.io for more information regarding library specifics - -from pycoproc_1 import Pycoproc -from LIS2HH12 import LIS2HH12 -from SI7006A20 import SI7006A20 -from LTR329ALS01 import LTR329ALS01 -from MPL3115A2 import MPL3115A2,ALTITUDE,PRESSURE - -py = Pycoproc(Pycoproc.PYSENSE) -mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals -si = SI7006A20(py) -lt = LTR329ALS01(py) -li = LIS2HH12(py) - -import _thread -from time import sleep -import uos - -def send_sensor_data(): - h2 = None - t2 = None - l2 = None - while (pybytes): - h = round(si.humidity(),1) - t = round(si.temperature(),1) - l = lt.light() - if h != h2: - print('humidity', h) - pybytes.send_signal(1, h) - h2=h - if t != t2: - print('temperature', t) - pybytes.send_signal(2, t) - t2=t - if l != l2: - print('luminocity', l) - pybytes.send_signal(3, l) - l2=l - sleep(10) - -# _thread.start_new_thread(send_sensor_data, ()) -send_sensor_data() diff --git a/shields/pysense_2.py b/shields/pysense_2.py index c7e1697..28495a1 100644 --- a/shields/pysense_2.py +++ b/shields/pysense_2.py @@ -27,6 +27,12 @@ if py.read_product_id() != Pycoproc.USB_PID_PYSENSE: raise Exception('Not a Pysense') +pybytes_enabled = False +if 'pybytes' in globals(): + if(pybytes.isconnected()): + print('Pybytes is connected, sending signals to Pybytes') + pybytes_enabled = True + mp = MPL3115A2(py,mode=ALTITUDE) # Returns height in meters. Mode may also be set to PRESSURE, returning a value in Pascals print("MPL3115A2 temperature: " + str(mp.temperature())) print("Altitude: " + str(mp.altitude())) @@ -50,3 +56,17 @@ print("Pitch: " + str(li.pitch())) print("Battery voltage: " + str(py.read_battery_voltage())) + +# set your battery voltage limits here +vmax = 4.2 +vmin = 3.3 +battery_voltage = py.read_battery_voltage() +battery_percentage = (battery_voltage - vmin / (vmax - vmin))*100 +print("Battery voltage: " + str(py.read_battery_voltage()), " percentage: ", battery_percentage) +if(pybytes_enabled): + pybytes.send_signal(1, mpp.pressure()) + pybytes.send_signal(2, si.temperature()) + pybytes.send_signal(3, lt.light()) + pybytes.send_signal(4, li.acceleration()) + pybytes.send_battery_level(int(battery_percentage)) + print("Sent data to pybytes") \ No newline at end of file diff --git a/shields/pytrack_1.py b/shields/pytrack_1.py index 4751617..cab1cb9 100644 --- a/shields/pytrack_1.py +++ b/shields/pytrack_1.py @@ -34,6 +34,12 @@ py = Pycoproc(Pycoproc.PYTRACK) l76 = L76GNSS(py, timeout=30) +pybytes_enabled = False +if 'pybytes' in globals(): + if(pybytes.isconnected()): + print('Pybytes is connected, sending signals to Pybytes') + pybytes_enabled = True + # sd = SD() # os.mount(sd, '/sd') # f = open('/sd/gps-record.txt', 'w') @@ -42,3 +48,13 @@ coord = l76.coordinates() #f.write("{} - {}\n".format(coord, rtc.now())) print("{} - {} - {}".format(coord, rtc.now(), gc.mem_free())) + if(pybytes_enabled): + pybytes.send_signal(1, coord) + time.sleep(10) + +""" +# sleep procedure +time.sleep(3) +py.setup_sleep(10) +py.go_to_sleep() +""" diff --git a/shields/pytrack_1_pybytes.py b/shields/pytrack_1_pybytes.py deleted file mode 100644 index 51e03ab..0000000 --- a/shields/pytrack_1_pybytes.py +++ /dev/null @@ -1,51 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019, Pycom Limited. -# -# This software is licensed under the GNU GPL version 3 or any -# later version, with permitted additional terms. For more information -# see the Pycom Licence v1.0 document supplied with this file, or -# available at https://www.pycom.io/opensource/licensing -# - -import machine -import math -import network -import os -import time -import utime -from machine import RTC -from machine import SD -from machine import Timer -from L76GNSS import L76GNSS -from pycoproc_1 import Pycoproc -from LIS2HH12 import LIS2HH12 -# setup as a station - -import gc - -time.sleep(2) -gc.enable() - -# setup rtc -rtc = machine.RTC() -rtc.ntp_sync("pool.ntp.org") -utime.sleep_ms(750) -print('\nRTC Set from NTP to UTC:', rtc.now()) -utime.timezone(7200) -print('Adjusted from UTC to EST timezone', utime.localtime(), '\n') -py = Pycoproc(Pycoproc.PYTRACK) -l76 = L76GNSS(py, timeout=30) -chrono = Timer.Chrono() -chrono.start() -li = LIS2HH12(py) -#sd = SD() -#os.mount(sd, '/sd') -#f = open('/sd/gps-record.txt', 'w') -while (pybytes): - coord = l76.coordinates() - #f.write("{} - {}\n".format(coord, rtc.now())) - print('Sending data', coord) - pybytes.send_signal(1, coord) - pybytes.send_signal(2, li.acceleration()) - time.sleep(10) diff --git a/shields/pytrack_2.py b/shields/pytrack_2.py index 8627e22..52fe547 100644 --- a/shields/pytrack_2.py +++ b/shields/pytrack_2.py @@ -42,15 +42,23 @@ time.sleep(1) l76 = L76GNSS(py, timeout=30, buffer=512) +pybytes_enabled = False +if 'pybytes' in globals(): + if(pybytes.isconnected()): + print('Pybytes is connected, sending signals to Pybytes') + pybytes_enabled = True + # sd = SD() # os.mount(sd, '/sd') # f = open('/sd/gps-record.txt', 'w') -# while (True): -for _ in range(5): +while (True): coord = l76.coordinates() #f.write("{} - {}\n".format(coord, rtc.now())) print("{} - {} - {}".format(coord, rtc.now(), gc.mem_free())) + if(pybytes_enabled): + pybytes.send_signal(1, coord) + time.sleep(10) """ # sleep procedure From 7b3fadc3e2ea183861ef3dad254201ea2bb36427 Mon Sep 17 00:00:00 2001 From: Adrian McEwen Date: Thu, 14 Mar 2019 11:14:56 +0000 Subject: [PATCH 30/39] Spot when pressure sensor has stalled and reset it. --- shields/lib/MPL3115A2.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/shields/lib/MPL3115A2.py b/shields/lib/MPL3115A2.py index b0a44c7..ce90631 100644 --- a/shields/lib/MPL3115A2.py +++ b/shields/lib/MPL3115A2.py @@ -79,8 +79,10 @@ def __init__(self, pysense = None, sda = 'P22', scl = 'P21', mode = PRESSURE): raise MPL3115A2exception("Error with MPL3115A2") def _read_status(self): - while True: + read_attempts = 0 + while read_attempts < 500: self.i2c.readfrom_mem_into(MPL3115_I2CADDR, MPL3115_STATUS, self.STA_reg) + read_attempts += 1 if(self.STA_reg[0] == 0): time.sleep(0.01) @@ -90,6 +92,11 @@ def _read_status(self): else: return False + # If we get here the sensor isn't responding. Reset it so next time in it should work + self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0x00])) # put into standby + self.i2c.writeto_mem(MPL3115_I2CADDR, MPL3115_CTRL_REG1, bytes([0x04])) # reset + return False + def pressure(self): if self.mode == ALTITUDE: raise MPL3115A2exception("Incorrect Measurement Mode MPL3115A2") From 08f2f85c075f1765279365e6d8d6726095da207a Mon Sep 17 00:00:00 2001 From: Adrian McEwen Date: Sat, 6 Apr 2019 12:35:20 +0100 Subject: [PATCH 31/39] Add lux calculation to LTR329ALS sensor --- shields/lib/LTR329ALS01.py | 34 ++++++++++++++++++++++++++++++++++ 1 file changed, 34 insertions(+) diff --git a/shields/lib/LTR329ALS01.py b/shields/lib/LTR329ALS01.py index 9087156..fc84e15 100644 --- a/shields/lib/LTR329ALS01.py +++ b/shields/lib/LTR329ALS01.py @@ -28,6 +28,14 @@ class LTR329ALS01: ALS_GAIN_8X = const(0x03) ALS_GAIN_48X = const(0x06) ALS_GAIN_96X = const(0x07) + ALS_GAIN_VALUES = { + ALS_GAIN_1X: 1, + ALS_GAIN_2X: 2, + ALS_GAIN_4X: 4, + ALS_GAIN_8X: 8, + ALS_GAIN_48X: 48, + ALS_GAIN_96X: 96 + } ALS_INT_50 = const(0x01) ALS_INT_100 = const(0x00) @@ -37,6 +45,16 @@ class LTR329ALS01: ALS_INT_300 = const(0x06) ALS_INT_350 = const(0x07) ALS_INT_400 = const(0x03) + ALS_INT_VALUES = { + ALS_INT_50: 0.5, + ALS_INT_100: 1, + ALS_INT_150: 1.5, + ALS_INT_200: 2, + ALS_INT_250: 2.5, + ALS_INT_300: 3, + ALS_INT_350: 3.5, + ALS_INT_400: 4 + } ALS_RATE_50 = const(0x00) ALS_RATE_100 = const(0x01) @@ -51,6 +69,9 @@ def __init__(self, pysense = None, sda = 'P22', scl = 'P21', gain = ALS_GAIN_1X, else: self.i2c = I2C(0, mode=I2C.MASTER, pins=(sda, scl)) + self.gain = gain + self.integration = integration + contr = self._getContr(gain) self.i2c.writeto_mem(ALS_I2CADDR, ALS_CONTR_REG, bytearray([contr])) @@ -78,3 +99,16 @@ def light(self): data0 = int(self._getWord(ch0high[0], ch0low[0])) return (data0, data1) + + def lux(self): + # Calculate Lux value from formula in Appendix A of the datasheet + light_level = self.light() + ratio = light_level[1]/(light_level[0]+light_level[1]) + if ratio < 0.45: + return (1.7743 * light_level[0] + 1.1059 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + elif ratio < 0.64 and ratio >= 0.45: + return (4.2785 * light_level[0] - 1.9548 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + elif ratio < 0.85 and ratio >= 0.64: + return (0.5926 * light_level[0] + 0.1185 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + else: + return 0 From 69414b207f038c6859d4cbec7ff56ada7bf1a638 Mon Sep 17 00:00:00 2001 From: Adrian McEwen Date: Fri, 3 May 2019 14:39:04 +0100 Subject: [PATCH 32/39] Fix division-by-zero bug in the lux() calculation --- shields/lib/LTR329ALS01.py | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/shields/lib/LTR329ALS01.py b/shields/lib/LTR329ALS01.py index fc84e15..8915ac4 100644 --- a/shields/lib/LTR329ALS01.py +++ b/shields/lib/LTR329ALS01.py @@ -71,7 +71,7 @@ def __init__(self, pysense = None, sda = 'P22', scl = 'P21', gain = ALS_GAIN_1X, self.gain = gain self.integration = integration - + contr = self._getContr(gain) self.i2c.writeto_mem(ALS_I2CADDR, ALS_CONTR_REG, bytearray([contr])) @@ -101,14 +101,17 @@ def light(self): return (data0, data1) def lux(self): - # Calculate Lux value from formula in Appendix A of the datasheet + # Calculate Lux value from formular in Appendix A of the datasheet light_level = self.light() - ratio = light_level[1]/(light_level[0]+light_level[1]) - if ratio < 0.45: - return (1.7743 * light_level[0] + 1.1059 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] - elif ratio < 0.64 and ratio >= 0.45: - return (4.2785 * light_level[0] - 1.9548 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] - elif ratio < 0.85 and ratio >= 0.64: - return (0.5926 * light_level[0] + 0.1185 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + if light_level[0]+light_level[1] > 0: + ratio = light_level[1]/(light_level[0]+light_level[1]) + if ratio < 0.45: + return (1.7743 * light_level[0] + 1.1059 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + elif ratio < 0.64 and ratio >= 0.45: + return (4.2785 * light_level[0] - 1.9548 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + elif ratio < 0.85 and ratio >= 0.64: + return (0.5926 * light_level[0] + 0.1185 * light_level[1]) / self.ALS_GAIN_VALUES[self.gain] / self.ALS_INT_VALUES[self.integration] + else: + return 0 else: return 0 From 4fd80bc9f425750ebd4aa577d12e1c37a44aef0a Mon Sep 17 00:00:00 2001 From: Adrian McEwen Date: Thu, 12 Dec 2019 15:30:21 +0000 Subject: [PATCH 33/39] Add methods to control the heater in the SI7006 temp/humidity sensor. --- shields/lib/SI7006A20.py | 28 ++++++++++++++++++++++++++-- 1 file changed, 26 insertions(+), 2 deletions(-) diff --git a/shields/lib/SI7006A20.py b/shields/lib/SI7006A20.py index d9a4025..f49a302 100644 --- a/shields/lib/SI7006A20.py +++ b/shields/lib/SI7006A20.py @@ -22,8 +22,18 @@ class SI7006A20: SI7006A20_I2C_ADDR = const(0x40) + # I2C commands TEMP_NOHOLDMASTER = const(0xF3) HUMD_NOHOLDMASTER = const(0xF5) + WRITE_USER_REG1 = const(0xE6) + READ_USER_REG1 = const(0xE7) + WRITE_HEATER_CTRL_REG = const(0x51) + READ_HEATER_CTRL_REG = const(0x11) + + # Register masks and offsets + USER_REG1_HTR_ENABLE_MASK = const(0b00000100) + USER_REG1_HTR_ENABLE_OFFSET = const(0x02) + HTR_CTRL_REG_MASK = const(0b00001111) def __init__(self, pysense = None, sda = 'P22', scl = 'P21'): if pysense is not None: @@ -55,18 +65,32 @@ def humidity(self): def read_user_reg(self): """ reading the user configuration register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xE7])) + self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([READ_USER_REG1])) time.sleep(0.5) data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) return data[0] def read_heater_reg(self): """ reading the heater configuration register """ - self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0x11])) + self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([READ_HEATER_CTRL_REG])) time.sleep(0.5) data = self.i2c.readfrom(SI7006A20_I2C_ADDR, 1) return data[0] + def write_heater_reg(self, heater_value): + """ writing the heater configuration register """ + # We should only set the bottom four bits of this register + heater_setting = heater_value & HTR_CTRL_REG_MASK + self.write_reg(WRITE_HEATER_CTRL_REG, heater_setting) + + def heater_control(self, on_off): + """ turn the heater on or off """ + # Get current settings for everything else + user_reg = self.read_user_reg() + # Set the heater bit + user_reg = (user_reg & ~USER_REG1_HTR_ENABLE_MASK) | (on_off << USER_REG1_HTR_ENABLE_OFFSET) + self.write_reg(WRITE_USER_REG1, user_reg) + def read_electronic_id(self): """ reading electronic identifier """ self.i2c.writeto(SI7006A20_I2C_ADDR, bytearray([0xFA]) + bytearray([0x0F])) From f9123010a17fed12f2612999b803bac27fce590b Mon Sep 17 00:00:00 2001 From: gijsio <67470426+gijsio@users.noreply.github.com> Date: Fri, 23 Apr 2021 14:54:51 +0200 Subject: [PATCH 34/39] add lux reading in example --- shields/pysense_2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shields/pysense_2.py b/shields/pysense_2.py index 28495a1..4edcd95 100644 --- a/shields/pysense_2.py +++ b/shields/pysense_2.py @@ -48,7 +48,7 @@ lt = LTR329ALS01(py) -print("Light (channel Blue lux, channel Red lux): " + str(lt.light())) +print("Light (channel Blue, channel Red): " + str(lt.light()," Lux: ", str(lt.lux()), "lx")) li = LIS2HH12(py) print("Acceleration: " + str(li.acceleration())) From 148a43996b415ae9ee5dce6a7b7a26944f300635 Mon Sep 17 00:00:00 2001 From: gijsio <67470426+gijsio@users.noreply.github.com> Date: Wed, 5 May 2021 15:13:25 +0200 Subject: [PATCH 35/39] MFRC630: Fix decoding not returning the data, but all 0's Fix for https://forum.pycom.io/topic/6981/pyscan-nfc-rfid-reading-issue/ Decoding a NFC card would previously return all 0's because of this bug. Instead of returning the data, we would return the length, which would make the following function calls print all 0's instead of the decoded data. I was not able to test this personally because of a lack of decodable keycards --- shields/lib/MFRC630.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shields/lib/MFRC630.py b/shields/lib/MFRC630.py index 574bc40..0d6c2f2 100644 --- a/shields/lib/MFRC630.py +++ b/shields/lib/MFRC630.py @@ -370,7 +370,7 @@ def mfrc630_MF_read_block(self, block_address, dest): buffer_length = self.mfrc630_fifo_length() rx_len = buffer_length if (buffer_length <= 16) else 16 dest = self.mfrc630_read_fifo(rx_len) - return rx_len + return dest def mfrc630_iso14443a_WUPA_REQA(self, instruction): From 59dd4ca0c679b6f83fc40c3aa4b495b1d8c01d81 Mon Sep 17 00:00:00 2001 From: Leonardo Merza Date: Thu, 27 May 2021 11:02:14 -0400 Subject: [PATCH 36/39] fix broken link --- lib/sqnsupgrade/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lib/sqnsupgrade/README.md b/lib/sqnsupgrade/README.md index 7646d50..e6ec433 100644 --- a/lib/sqnsupgrade/README.md +++ b/lib/sqnsupgrade/README.md @@ -12,7 +12,7 @@ Please start with the following steps: 1. Upgrade the Pycom Firmware Updater tool to latest version 2. Select Firmware Type `stable` in the communication window to upgrade to latest stable version -You can find the different versions of firmwares available here: http://software.pycom.io/downloads/sequans2.html​ +You can find the different versions of firmwares available here: http://software.pycom.io/downloads/sequans2.html These files are password protected, to download them you should be a forum.pycom.io member and access to: Announcements & News --> Announcements only for members --> Firmware Files for Sequans LTE modem now are secured, or clicking Here From b92cea79b32fc89bff4153f5f5f0840a988a52d2 Mon Sep 17 00:00:00 2001 From: gijsio <67470426+gijsio@users.noreply.github.com> Date: Tue, 15 Jun 2021 09:11:09 +0200 Subject: [PATCH 37/39] Depracation notice (#148) * Create readme.md * for reference only * partition -> part --- pymesh/readme.md | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 pymesh/readme.md diff --git a/pymesh/readme.md b/pymesh/readme.md new file mode 100644 index 0000000..0be1a7a --- /dev/null +++ b/pymesh/readme.md @@ -0,0 +1,3 @@ +# For reference only + +This library is the open-source part of the Pymesh LoRa Firmware which can be provisioned through Pybytes and cannot be used as stand-alone on a Pybytes or Pygate type firmware. Please check the [Pycom Documentation](https://docs.pycom.io/pybytes/pymeshintegration/provisioning/) on how to get Pymesh type firmware provisioned to your device. You will not have to use this library in your project or flash it to your device separately, as it is already included in the firmware. From 478211f5873f90aebff99ea8dd83c9379867dd8e Mon Sep 17 00:00:00 2001 From: gijsio <67470426+gijsio@users.noreply.github.com> Date: Thu, 17 Jun 2021 16:58:10 +0200 Subject: [PATCH 38/39] added missing parentheses --- shields/pysense_2.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/shields/pysense_2.py b/shields/pysense_2.py index 4edcd95..ff793e7 100644 --- a/shields/pysense_2.py +++ b/shields/pysense_2.py @@ -48,7 +48,7 @@ lt = LTR329ALS01(py) -print("Light (channel Blue, channel Red): " + str(lt.light()," Lux: ", str(lt.lux()), "lx")) +print("Light (channel Blue, channel Red): " + str(lt.light())," Lux: ", str(lt.lux()), "lx") li = LIS2HH12(py) print("Acceleration: " + str(li.acceleration())) @@ -69,4 +69,4 @@ pybytes.send_signal(3, lt.light()) pybytes.send_signal(4, li.acceleration()) pybytes.send_battery_level(int(battery_percentage)) - print("Sent data to pybytes") \ No newline at end of file + print("Sent data to pybytes") From 75d0e67cb421e0576a3a9677bb0d9d81f27ebdb7 Mon Sep 17 00:00:00 2001 From: Peter Putz Date: Wed, 27 Oct 2021 14:39:49 +0200 Subject: [PATCH 39/39] pymesh: do not (re-)create LoRa instances in pymesh_config It seems there is a rare chance to end up with a frozen device at the point where the lora=LoRa() object is recreated. There is no real need to do this inside pymesh_config, so as a workaround we simply make one object only and pass the lora_mac --- pymesh/pymesh_frozen/lib/pymesh_config.py | 12 ++++-------- pymesh/pymesh_frozen/lorawan/main.py | 9 +++++++-- pymesh/pymesh_frozen/main.py | 9 +++++++-- pymesh/pymesh_frozen/main_BR.py | 7 ++++++- 4 files changed, 24 insertions(+), 13 deletions(-) diff --git a/pymesh/pymesh_frozen/lib/pymesh_config.py b/pymesh/pymesh_frozen/lib/pymesh_config.py index 798f8f8..74a0292 100644 --- a/pymesh/pymesh_frozen/lib/pymesh_config.py +++ b/pymesh/pymesh_frozen/lib/pymesh_config.py @@ -5,7 +5,6 @@ see the Pycom Licence v1.0 document supplied with this file, or available at https://www.pycom.io/opensource/licensing ''' -import ubinascii import json from network import LoRa @@ -78,10 +77,7 @@ def write_config(pymesh_config, force_restart = False): time.sleep(1) machine.deepsleep(1000) - def check_mac(pymesh_config): - lora = LoRa(mode=LoRa.LORA, region= LoRa.EU868) - MAC = int(str(ubinascii.hexlify(lora.mac()))[2:-1], 16) - + def check_mac(pymesh_config, MAC): if pymesh_config.get('MAC') is None: # if MAC config unspecified, set it to LoRa MAC print_debug(3, "Set MAC in config file as " + str(MAC)) @@ -102,7 +98,7 @@ def check_mac(pymesh_config): print_debug(3, "MAC ok" + str(MAC)) - def read_config(): + def read_config(MAC): file = PymeshConfig.CONFIG_FILENAME pymesh_config = {} error_file = True @@ -138,10 +134,10 @@ def read_config(): pymesh_config['br_ena'] = PymeshConfig.BR_ENABLE pymesh_config['br_prio'] = PymeshConfig.BR_PRIORITY - PymeshConfig.check_mac(pymesh_config) + PymeshConfig.check_mac(pymesh_config, MAC) print_debug(3, "Default settings:" + str(pymesh_config)) PymeshConfig.write_config(pymesh_config, True) - PymeshConfig.check_mac(pymesh_config) + PymeshConfig.check_mac(pymesh_config, MAC) print_debug(3, "Settings:" + str(pymesh_config)) return pymesh_config diff --git a/pymesh/pymesh_frozen/lorawan/main.py b/pymesh/pymesh_frozen/lorawan/main.py index 223cee6..33f33da 100644 --- a/pymesh/pymesh_frozen/lorawan/main.py +++ b/pymesh/pymesh_frozen/lorawan/main.py @@ -1,5 +1,7 @@ -import pycom import time +import ubinascii +import pycom +from network import LoRa try: from pymesh_config import PymeshConfig @@ -28,8 +30,11 @@ def new_message_cb(rcv_ip, rcv_port, rcv_data): pycom.heartbeat(False) +lora = LoRa(mode=LoRa.LORA, region= LoRa.EU868) +lora_mac = int(str(ubinascii.hexlify(lora.mac()))[2:-1], 16) + # read config file, or set default values -pymesh_config = PymeshConfig.read_config() +pymesh_config = PymeshConfig.read_config(lora_mac) #initialize Pymesh pymesh = Pymesh(pymesh_config, new_message_cb) diff --git a/pymesh/pymesh_frozen/main.py b/pymesh/pymesh_frozen/main.py index 4cf6fbd..5d7c17a 100644 --- a/pymesh/pymesh_frozen/main.py +++ b/pymesh/pymesh_frozen/main.py @@ -1,5 +1,7 @@ -import pycom import time +import ubinascii +import pycom +from network import LoRa try: from pymesh_config import PymeshConfig @@ -28,8 +30,11 @@ def new_message_cb(rcv_ip, rcv_port, rcv_data): pycom.heartbeat(False) +lora = LoRa(mode=LoRa.LORA, region= LoRa.EU868) +lora_mac = int(str(ubinascii.hexlify(lora.mac()))[2:-1], 16) + # read config file, or set default values -pymesh_config = PymeshConfig.read_config() +pymesh_config = PymeshConfig.read_config(lora_mac) #initialize Pymesh pymesh = Pymesh(pymesh_config, new_message_cb) diff --git a/pymesh/pymesh_frozen/main_BR.py b/pymesh/pymesh_frozen/main_BR.py index 3c53257..fdb9780 100644 --- a/pymesh/pymesh_frozen/main_BR.py +++ b/pymesh/pymesh_frozen/main_BR.py @@ -1,5 +1,7 @@ import time +import ubinascii import pycom +from network import LoRa # 2 = test pybytes OTA feature # 4 = added device_id (pybytes token) in the packets to BR @@ -66,8 +68,11 @@ def new_br_message_cb(rcv_ip, rcv_port, rcv_data, dest_ip, dest_port): pycom.heartbeat(False) +lora = LoRa(mode=LoRa.LORA, region= LoRa.EU868) +lora_mac = int(str(ubinascii.hexlify(lora.mac()))[2:-1], 16) + # read config file, or set default values -pymesh_config = PymeshConfig.read_config() +pymesh_config = PymeshConfig.read_config(lora_mac) #initialize Pymesh pymesh = Pymesh(pymesh_config, new_message_cb)