├── .gitignore ├── template ├── double_template.py ├── dut_template.py ├── serial_interface_upython.py └── test_template.py ├── images ├── blink.gif ├── method.png └── ambiente_ok.png ├── SPI ├── pre-built-firmware │ └── firmware.bin ├── mymodules │ └── spi_slave │ │ ├── micropython.mk │ │ ├── functions.h │ │ ├── spi_slave.c │ │ └── functions.c ├── double_slave.py ├── dut_master.py ├── serial_interface_upython.py ├── README.md └── test_master_slave.py ├── requirements.txt ├── BLE ├── dut_sensor.py ├── double_cellphone.py ├── README.md ├── serial_interface_upython.py ├── ble_temperature.py ├── ble_advertising.py ├── test_sensor_cellphone.py └── ble_temperature_central.py ├── conftime_DS3231 ├── dut_conf_time.py ├── README.md ├── serial_interface_upython.py ├── double_DS3231.py ├── DS3231.py └── test_conftime_DS3231.py ├── GPS ├── dut_positioning.py ├── README.md ├── double_GPS.py ├── serial_interface_upython.py ├── test_positioning_GPS_itself.py ├── test_positioning_GPS.py └── adafruit_gps.py ├── blink_led ├── README.md ├── dut_blink.py ├── double_led.py ├── serial_interface_upython.py └── test_blink_led.py └── README.md /.gitignore: -------------------------------------------------------------------------------- 1 | *.mpy 2 | *.ras 3 | __pycache__ 4 | test-env 5 | ThirdDocs 6 | -------------------------------------------------------------------------------- /template/double_template.py: -------------------------------------------------------------------------------- 1 | class Double_class(object): 2 | def __init__(self): 3 | pass -------------------------------------------------------------------------------- /template/dut_template.py: -------------------------------------------------------------------------------- 1 | class Dut_class(object): 2 | def __init__(self): 3 | pass 4 | -------------------------------------------------------------------------------- /images/blink.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/saramonteiro/micropython_test_lib/HEAD/images/blink.gif -------------------------------------------------------------------------------- /images/method.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/saramonteiro/micropython_test_lib/HEAD/images/method.png -------------------------------------------------------------------------------- /images/ambiente_ok.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/saramonteiro/micropython_test_lib/HEAD/images/ambiente_ok.png -------------------------------------------------------------------------------- /SPI/pre-built-firmware/firmware.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/saramonteiro/micropython_test_lib/HEAD/SPI/pre-built-firmware/firmware.bin -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- 1 | adafruit-ampy==1.0.7 2 | Click==7.0 3 | future==0.18.2 4 | iso8601==0.1.12 5 | mpy-cross==1.11 6 | pkg-resources==0.0.0 7 | pyserial==3.4 8 | python-dotenv==0.10.3 9 | PyYAML==5.2 10 | should-dsl==2.1.2 11 | -------------------------------------------------------------------------------- /SPI/mymodules/spi_slave/micropython.mk: -------------------------------------------------------------------------------- 1 | EXAMPLE_MOD_DIR := $(USERMOD_DIR) 2 | 3 | # Add all C files to SRC_USERMOD. 4 | SRC_USERMOD += $(EXAMPLE_MOD_DIR)/functions.c 5 | SRC_USERMOD += $(EXAMPLE_MOD_DIR)/spi_slave.c 6 | 7 | # We can add our module folder to include paths if needed 8 | # This is not actually needed in this example. 9 | CFLAGS_USERMOD += -I$(EXAMPLE_MOD_DIR) -------------------------------------------------------------------------------- /SPI/double_slave.py: -------------------------------------------------------------------------------- 1 | import spi_slave 2 | 3 | class Double_slave(object): 4 | def __init__(self, mosi, miso, sclk, cs): 5 | spi_slave.init(mosi,miso,sclk,cs); 6 | 7 | def enable_transaction(self, send_buffer): 8 | return spi_slave.enable_transaction(send_buffer) 9 | 10 | def get_received_buffer(self): 11 | return list(spi_slave.get_received_buffer()) 12 | 13 | def deinit(self): 14 | return spi_slave.free_bus() 15 | 16 | -------------------------------------------------------------------------------- /SPI/mymodules/spi_slave/functions.h: -------------------------------------------------------------------------------- 1 | #include "py/obj.h" 2 | #include "py/runtime.h" 3 | #include 4 | 5 | typedef struct last_trans_info 6 | { 7 | uint8_t * recv_buffer_pointer; 8 | uint8_t size; 9 | }last_trans_info_t; 10 | 11 | mp_obj_t spi_slave_init(mp_uint_t, const mp_obj_t *); 12 | mp_obj_t spi_slave_free_bus(void); 13 | mp_obj_t spi_slave_enable_transaction(mp_obj_t); 14 | mp_obj_t spi_slave_get_received_buffer(); 15 | 16 | -------------------------------------------------------------------------------- /BLE/dut_sensor.py: -------------------------------------------------------------------------------- 1 | from ble_temperature import BLETemperature 2 | import bluetooth 3 | 4 | class BLE_Sensor(object): 5 | 6 | def __init__(self, name): 7 | self.ble = bluetooth.BLE() 8 | self.sensor = BLETemperature(self.ble, name) 9 | 10 | def set_value(self, value, notification = False): 11 | self.sensor.set_temperature(value, notification) 12 | 13 | def deinit(self): 14 | self.ble.gap_advertise(None) 15 | self.ble.active(False) 16 | -------------------------------------------------------------------------------- /conftime_DS3231/dut_conf_time.py: -------------------------------------------------------------------------------- 1 | from machine import I2C, Pin 2 | import DS3231 3 | 4 | class ConfTime(object): 5 | 6 | def __init__(self, sda, scl): 7 | self.i2c = I2C(sda = Pin(sda), scl=Pin(scl)) 8 | self.rtc = DS3231.DS3231(self.i2c) 9 | 10 | def set_date_time(self, my_date_time): 11 | self.rtc.DateTime(my_date_time) 12 | 13 | def get_date_time(self): 14 | return self.rtc.DateTime() 15 | 16 | 17 | # "Follow your Bliss" - Joseph Campbell -------------------------------------------------------------------------------- /GPS/dut_positioning.py: -------------------------------------------------------------------------------- 1 | from machine import UART 2 | import utime as time 3 | from adafruit_gps import GPS 4 | 5 | class Positioning(object): 6 | def __init__(self, TX, RX, uart): 7 | self.uart = UART(uart, baudrate=9600) 8 | self.uart.init(9600,bits=8,tx=TX,rx=RX) 9 | self.gps = GPS(self.uart) 10 | 11 | def send_command(self, command): 12 | self.gps.send_command(command) 13 | 14 | def received_command(self): 15 | command = self.uart.readline() 16 | if(command != None): 17 | return command 18 | else: 19 | return None 20 | 21 | def get_latitude(self): 22 | self.gps.update() 23 | return self.gps.latitude 24 | 25 | def deinit(self): 26 | self.uart.deinit() 27 | 28 | # "Difficulties make ordinary people become extraordinary-people" - 29 | -------------------------------------------------------------------------------- /BLE/double_cellphone.py: -------------------------------------------------------------------------------- 1 | from ble_temperature_central import BLETemperatureCentral 2 | import bluetooth 3 | 4 | class DOUBLE_cellphone(object): 5 | 6 | def __init__(self): 7 | self.ble = bluetooth.BLE() 8 | self.central_scanner = BLETemperatureCentral(self.ble) 9 | self.flag_not_found = False 10 | self.central_scanner.scan(callback=self.on_scan_callback) 11 | 12 | 13 | def on_scan_callback(self, addr_type, addr, name): 14 | if addr_type is not None: 15 | self.central_scanner.connect() 16 | else: 17 | self.flag_not_found = True 18 | 19 | def check_connectivity(self): 20 | return self.central_scanner.is_connected() 21 | 22 | def read_value(self): 23 | return self.central_scanner.value() 24 | 25 | def issue_reading(self): 26 | self.central_scanner.read(None) 27 | 28 | def deinit(self): 29 | self.ble.gap_scan(None) 30 | self.ble.active(False) 31 | 32 | -------------------------------------------------------------------------------- /GPS/README.md: -------------------------------------------------------------------------------- 1 | # GPS Demo - UART 2 | 3 | This example shows how to test a UART driver. For this purpose, the DOUBLE plays the role of a GPS peripheral. Besides the test, it also can be very useful when the GPS signal is out and you need to get a fake NMEA sentence. 4 | There are two tests. The one that ends with "itself" uses a second UART from the DUT to simulate the GPS and doesn't use another board as DOUBLE. This means that in the absence of another esp32 you may use only one board depending on what you want to test, 5 | 6 | ## Firmwares 7 | DUT: [micropython original firmware](http://micropython.org/download#esp32). 8 | 9 | DOUBLE: [micropython original firmware](http://micropython.org/download#esp32). 10 | 11 | ## How to run it: 12 | ``` 13 | python3 test_positioning_GPS.py -v 14 | ``` 15 | 16 | ## Electrical Connections 17 | 18 | | DUT | | DOUBLE | | 19 | ---- | ---- | ---- | ---- 20 | RX | TX | RX | TX 21 | 16 | 17 | 16 | 22 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /conftime_DS3231/README.md: -------------------------------------------------------------------------------- 1 | # DS3231 Demo - I2C 2 | This example shows how to test a I2C driver. The DOUBLE plays the role of the RTC DS3231. The test will verify if the DUT is correctly setting and getting datetime info. The DOUBLE uses an internal timer to simulate the RTC behavior. It is transparent, so if you replace a true RTC by the DOUBLE with a predefined datetime, the DUT will continue reading as if it was reading from a real RTC.  3 | 4 | ## Firmwares 5 | DUT: [micropython original firmware](http://micropython.org/download#esp32). 6 | 7 | DOUBLE: [micropython with i2c slave mode](https://github.com/loboris/MicroPython_ESP32_psRAM_LoBo/wiki/firmwares). 8 | 9 | ## How to run it: 10 | ``` 11 | python3 test_conftime_DS3231.py -v 12 | ``` 13 | 14 | ## Electrical Connections 15 | 16 | || DUT | DOUBLE 17 | ---- | ---- | ---- 18 | SDA | 21 | 21 19 | SCL | 22 | 22 20 | 21 | 22 | It's necessary to use one pull-up resistor in each bus. It was used 4,7K ohms during the tests. 23 | -------------------------------------------------------------------------------- /blink_led/README.md: -------------------------------------------------------------------------------- 1 | # Blink Led Demo 2 | 3 | When we start programming in microcontrollers, the most basic code we do is a blink led. It's a "hello world" for microcontroller! 4 | So, the first example here also tests a production code which blinks a led. The double here is playing the role of a led. 5 | 6 | ## Firmwares 7 | DUT: [micropython original firmware](http://micropython.org/download#esp32). 8 | 9 | DOUBLE: [micropython original firmware](http://micropython.org/download#esp32). 10 | 11 | ## How to run it: 12 | ``` 13 | python3 test_blink_led.py -v 14 | ``` 15 | 16 | ## Electrical Connections 17 | 18 | DUT | DOUBLE 19 | ------------ | ------------- 20 | 2 | 21 21 | 22 | Look at it! Here the DUT's output for led was intentionally PIN 2. This pin is connected to an embed led on devs Kit v1, and probably on other boards too. This allows us to see the led really blinking while the test is being performed. Only for visual purposes. 23 | 24 | ![blinking](https://github.com/saramonteiro/micropython_test_lib/blob/master/images/blink.gif) 25 | -------------------------------------------------------------------------------- /BLE/README.md: -------------------------------------------------------------------------------- 1 | # BLE Demo 2 | 3 | This example shows how to test a BLE connection and reading on a Peripheral device. Part of it uses the temperature sensor example provided [here](https://github.com/micropython/micropython/tree/master/examples/bluetooth). 4 | The DUT is playing the role of a Peripheral device that is a temperature sensor. The DOUBLE plays the role of a Central device like a smartphone. The test is going to verify if the Peripheral is rightly connecting to Central devices and if it's correcting providing data when requested. 5 | 6 | ## Firmwares 7 | DUT: [micropython original firmware](http://micropython.org/download#esp32). 8 | 9 | DOUBLE: [micropython original firmware](http://micropython.org/download#esp32). 10 | 11 | P.S: The BLE module is very recent and initialization time was indeterministic the last time it was tested, sometimes it causes test errors. So the results of the tests are unstable. 12 | 13 | ## How to run it: 14 | ``` 15 | python3 test_sensor_cellphone.py -v 16 | ``` 17 | Since the BLE is a wireless protocol, no wired connection is done. 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /blink_led/dut_blink.py: -------------------------------------------------------------------------------- 1 | from machine import Pin 2 | from machine import Timer 3 | import time 4 | 5 | class Blinker(object): 6 | def __init__(self, output_pin, period, pulses = None): 7 | # setup output pin 8 | self.output_pin = output_pin 9 | self.period = period 10 | self.pulses = pulses 11 | self.pin = Pin(self.output_pin,Pin.OUT) 12 | self.pin.off() 13 | self.counter = 0 14 | 15 | # Blocks the REPL until it has finished 16 | def blink_blocking(self): 17 | if self.pulses == None: 18 | while True: 19 | self.pin.value(not self.pin.value()) 20 | time.sleep_ms(int(self.period/2)) 21 | else: 22 | for i in range(0,(self.pulses)*2): 23 | self.pin.value(not self.pin.value()) 24 | time.sleep_ms(int(self.period/2)) 25 | 26 | def callback_timer(self,arg): 27 | self.pin.value(not self.pin.value()) 28 | if (self.pulses != None): 29 | self.counter+=1 30 | if(self.counter == (self.pulses*2)): 31 | self.timing.deinit() 32 | self.counter = 0 33 | 34 | def disable_isr(self): 35 | self.pin.off() 36 | self.timing.deinit() 37 | 38 | # Uses an interruption timer and callback function to trigger the toggle 39 | def blink_timer_isr(self): 40 | self.timing = Timer(-1) 41 | self.timing.init(period=int(self.period/2), mode=Timer.PERIODIC, callback=self.callback_timer) 42 | 43 | 44 | # "If I have seen further it is by standing on the shoulders of Giants." Isaac Newton 45 | -------------------------------------------------------------------------------- /SPI/mymodules/spi_slave/spi_slave.c: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include "py/obj.h" 5 | #include "py/runtime.h" 6 | #include "functions.h" 7 | 8 | STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(spi_slave_init_obj, 4, 4, spi_slave_init); 9 | STATIC MP_DEFINE_CONST_FUN_OBJ_0(spi_slave_free_bus_obj, spi_slave_free_bus); 10 | STATIC MP_DEFINE_CONST_FUN_OBJ_1(spi_slave_enable_transaction_obj, spi_slave_enable_transaction); 11 | STATIC MP_DEFINE_CONST_FUN_OBJ_0(spi_slave_get_received_buffer_obj, spi_slave_get_received_buffer); 12 | 13 | 14 | STATIC const mp_rom_map_elem_t spi_slave_module_globals_table[] = { 15 | { MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_spi_slave) }, 16 | { MP_ROM_QSTR(MP_QSTR_init), MP_ROM_PTR(&spi_slave_init_obj) }, 17 | { MP_ROM_QSTR(MP_QSTR_free_bus), MP_ROM_PTR(&spi_slave_free_bus_obj) }, 18 | { MP_ROM_QSTR(MP_QSTR_enable_transaction), MP_ROM_PTR(&spi_slave_enable_transaction_obj) }, 19 | { MP_ROM_QSTR(MP_QSTR_get_received_buffer), MP_ROM_PTR(&spi_slave_get_received_buffer_obj) }, 20 | }; 21 | 22 | STATIC MP_DEFINE_CONST_DICT(spi_slave_module_globals, spi_slave_module_globals_table); 23 | 24 | const mp_obj_module_t spi_slave_user_cmodule = { 25 | .base = { &mp_type_module }, 26 | .globals = (mp_obj_dict_t*)&spi_slave_module_globals, 27 | }; 28 | 29 | MP_REGISTER_MODULE(MP_QSTR_spi_slave, spi_slave_user_cmodule, MODULE_SPI_SLAVE_ENABLED); 30 | -------------------------------------------------------------------------------- /GPS/double_GPS.py: -------------------------------------------------------------------------------- 1 | from machine import UART 2 | from machine import Timer 3 | 4 | class DOUBLE_GPS(object): 5 | GGA_MESSAGE = b"$GPGGA,141623.523,2143.963,S,04111.493,W,1,12,1.0,0.0,M,0.0,M,,*65\n" 6 | RMC_MESSAGE = b"$GPRMC,141623.523,A,2143.963,S,04111.493,W,,,301019,000.0,W*7B\n" 7 | UPDATE_RATE_1S = 'PMTK220,1000' 8 | 9 | def __init__(self, TX, RX, uart): 10 | self.uart = UART(uart, baudrate=9600) 11 | self.uart.init(9600,bits=8,tx=TX,rx=RX) 12 | self.flag = False 13 | 14 | def make_data_available(self,NMEA_sentence): 15 | self.uart.write(NMEA_sentence) 16 | 17 | def received_command(self): 18 | command = self.uart.readline() 19 | if(command != None): 20 | command, received_check_sum = command.split(b'*') 21 | command = command.strip(b'$') 22 | received_check_sum = received_check_sum[0:2] 23 | generated_check_sum = self.generate_checksum(command) 24 | command = command.decode() 25 | if command == self.UPDATE_RATE_1S: 26 | self.continuous_mode() 27 | self.flag = True 28 | return command 29 | else: 30 | return None 31 | 32 | def generate_checksum(self, command): 33 | checksum = 0 34 | for char in command: 35 | checksum ^= char 36 | return checksum 37 | 38 | def continuous_mode(self): 39 | self.my_timer = Timer(1) 40 | self.my_timer.init(period=1000,mode=self.my_timer.PERIODIC, callback=self.my_callback) 41 | 42 | def my_callback(self,timer): 43 | self.make_data_available(self.RMC_MESSAGE) 44 | 45 | def deinit(self): 46 | self.uart.deinit() 47 | if hasattr(self, 'my_timer'): 48 | self.my_timer.deinit() -------------------------------------------------------------------------------- /blink_led/double_led.py: -------------------------------------------------------------------------------- 1 | from machine import Pin 2 | import time 3 | 4 | class Led(object): 5 | 6 | def __init__(self, input_pin, pulses): 7 | self.input_pin = input_pin 8 | self.pulses = pulses 9 | self.counter = 0 10 | self.frequency = 0 11 | self.acumulator = 0 12 | self.periods = [] 13 | self.start = 0 14 | # setup input pin 15 | self.pin = Pin(self.input_pin,Pin.IN, Pin.PULL_DOWN) 16 | 17 | def start_acquisition(self): 18 | # Enables digital input interruption 19 | self.pin.irq(trigger = Pin.IRQ_RISING, handler = self.ISR) 20 | 21 | # Calculate the average frequency 22 | def calculate_average_frequency(self): 23 | self.frequency = 1/(self.calculate_average_period()/1000) 24 | 25 | # Calculate the average period 26 | def calculate_average_period(self): 27 | self.period = self.acumulator/(self.pulses-1) 28 | return self.period 29 | 30 | def get_average_frequency(self): 31 | return self.frequency 32 | 33 | def get_average_period(self): 34 | return self.period 35 | 36 | def show_me_periods(self): 37 | print(self.periods) 38 | 39 | # Interrupt Service Routine 40 | def ISR(self,arg): 41 | if(self.counter < self.pulses): 42 | period = time.ticks_diff(time.ticks_ms(), self.start) 43 | self.start = time.ticks_ms() 44 | if(self.counter != 0): 45 | self.periods.append(period) 46 | self.acumulator += period 47 | self.counter+=1 48 | if(self.counter == self.pulses): 49 | self.calculate_average_period() 50 | self.disable_irq() 51 | 52 | # method to be improved 53 | def disable_irq(self): 54 | self.pin.irq(trigger=0,handler=self.ISR) 55 | 56 | -------------------------------------------------------------------------------- /SPI/dut_master.py: -------------------------------------------------------------------------------- 1 | from machine import Pin, SPI 2 | import time 3 | 4 | class Dut_master(object): 5 | def __init__(self, mosi, miso, sclk, cs): 6 | self.spi_master = SPI(1, baudrate=2000000,polarity=0, phase=0, bits=8, firstbit=0, sck=Pin(sclk), mosi=Pin(mosi), miso=Pin(miso)) 7 | self.cs = Pin(cs, Pin.OUT) 8 | self.cs.on(); 9 | self.delay = 0.050 10 | 11 | def read_registers_wo_address(self, num_readings): 12 | readings = b'' 13 | self.cs.off() 14 | time.sleep(self.delay) 15 | for i in range(0,num_readings): 16 | readings += self.spi_master.read(1) 17 | time.sleep(self.delay) 18 | self.cs.on() 19 | readings = list(readings) 20 | return readings 21 | 22 | def read_registers_w_address(self, address, num_readings): 23 | readings = b'' 24 | self.cs.off() 25 | time.sleep(self.delay) 26 | self.spi_master.write(bytes([address])) 27 | for i in range(0,num_readings): 28 | time.sleep(self.delay) 29 | readings += self.spi_master.read(1) 30 | time.sleep(self.delay) 31 | self.cs.on() 32 | readings = list(readings) 33 | return readings 34 | 35 | def write_registers_wo_address(self, values): 36 | self.cs.off() 37 | time.sleep(self.delay) 38 | for value in values: 39 | self.spi_master.write(bytes([value])) 40 | time.sleep(self.delay) 41 | self.cs.on() 42 | return len(values) 43 | 44 | def write_registers_w_address(self, address, values): 45 | self.cs.off() 46 | time.sleep(self.delay) 47 | self.spi_master.write(bytes([address])) 48 | for value in values: 49 | time.sleep(self.delay) 50 | self.spi_master.write(bytes([value])) 51 | time.sleep(self.delay) 52 | self.cs.on() 53 | return len(values) 54 | 55 | 56 | def deinit(self): 57 | self.spi_master.deinit() -------------------------------------------------------------------------------- /BLE/serial_interface_upython.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import time 4 | from time import sleep 5 | import serial 6 | import re 7 | 8 | class SerialInterface(object): 9 | def __init__(self,port, baud): 10 | self.port = port 11 | self.baud = baud 12 | 13 | def connect_to_serial(self): 14 | # print ('Opening serial port...') 15 | self.serial_connection = serial.Serial(self.port, self.baud) 16 | if self.serial_connection.isOpen(): 17 | # print ('port opened!\n') 18 | return(True) 19 | else: 20 | return(False) 21 | 22 | def close_serial(self): 23 | self.serial_connection.close() 24 | 25 | def clean_file_sys(self): 26 | self.repl("import os",0.1) 27 | files = self.repl("os.listdir()", 0.4)[2] 28 | files = files.decode() 29 | files = files.strip('[]') 30 | files = files.split(',') 31 | for i in range(len(files)): 32 | files[i] = files[i].replace('\'','') 33 | files[i] = files[i].strip(' ') 34 | for file in files[:]: 35 | if file != 'boot.py': 36 | self.repl("os.remove('"+file+"')",0.4) 37 | 38 | def repl(self, LINE, sleep_time): 39 | response = '' 40 | response = response.encode() 41 | self.serial_connection.flushInput() 42 | LINE = LINE.replace("\r", r'\r') 43 | LINE = "\r" + LINE + "\r" 44 | LINE = LINE.encode() 45 | self.serial_connection.write(LINE) 46 | sleep(sleep_time) 47 | # print(self.serial_connection.inWaiting()) 48 | while (self.serial_connection.inWaiting() > 0): 49 | response = response + self.serial_connection.read(self.serial_connection.inWaiting()) 50 | # print (response) 51 | response = re.sub('\r'.encode(), ''.encode(), response) 52 | sleep(sleep_time) 53 | response_list = response.split("\n".encode()) 54 | return response_list 55 | -------------------------------------------------------------------------------- /GPS/serial_interface_upython.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import time 4 | from time import sleep 5 | import serial 6 | import re 7 | 8 | class SerialInterface(object): 9 | def __init__(self,port, baud): 10 | self.port = port 11 | self.baud = baud 12 | 13 | def connect_to_serial(self): 14 | # print ('Opening serial port...') 15 | self.serial_connection = serial.Serial(self.port, self.baud) 16 | if self.serial_connection.isOpen(): 17 | # print ('port opened!\n') 18 | return(True) 19 | else: 20 | return(False) 21 | 22 | def close_serial(self): 23 | self.serial_connection.close() 24 | 25 | def clean_file_sys(self): 26 | self.repl("import os",0.1) 27 | files = self.repl("os.listdir()", 0.4)[2] 28 | files = files.decode() 29 | files = files.strip('[]') 30 | files = files.split(',') 31 | for i in range(len(files)): 32 | files[i] = files[i].replace('\'','') 33 | files[i] = files[i].strip(' ') 34 | for file in files[:]: 35 | if file != 'boot.py': 36 | self.repl("os.remove('"+file+"')",0.4) 37 | 38 | def repl(self, LINE, sleep_time): 39 | response = '' 40 | response = response.encode() 41 | self.serial_connection.flushInput() 42 | LINE = LINE.replace("\r", r'\r') 43 | LINE = "\r" + LINE + "\r" 44 | LINE = LINE.encode() 45 | self.serial_connection.write(LINE) 46 | sleep(sleep_time) 47 | # print(self.serial_connection.inWaiting()) 48 | while (self.serial_connection.inWaiting() > 0): 49 | response = response + self.serial_connection.read(self.serial_connection.inWaiting()) 50 | # print (response) 51 | response = re.sub('\r'.encode(), ''.encode(), response) 52 | sleep(sleep_time) 53 | response_list = response.split("\n".encode()) 54 | return response_list 55 | -------------------------------------------------------------------------------- /SPI/serial_interface_upython.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import time 4 | from time import sleep 5 | import serial 6 | import re 7 | 8 | class SerialInterface(object): 9 | def __init__(self,port, baud): 10 | self.port = port 11 | self.baud = baud 12 | 13 | def connect_to_serial(self): 14 | # print ('Opening serial port...') 15 | self.serial_connection = serial.Serial(self.port, self.baud) 16 | if self.serial_connection.isOpen(): 17 | # print ('port opened!\n') 18 | return(True) 19 | else: 20 | return(False) 21 | 22 | def close_serial(self): 23 | self.serial_connection.close() 24 | 25 | def clean_file_sys(self): 26 | self.repl("import os",0.1) 27 | files = self.repl("os.listdir()", 0.4)[2] 28 | files = files.decode() 29 | files = files.strip('[]') 30 | files = files.split(',') 31 | for i in range(len(files)): 32 | files[i] = files[i].replace('\'','') 33 | files[i] = files[i].strip(' ') 34 | for file in files[:]: 35 | if file != 'boot.py': 36 | self.repl("os.remove('"+file+"')",0.4) 37 | 38 | def repl(self, LINE, sleep_time): 39 | response = '' 40 | response = response.encode() 41 | self.serial_connection.flushInput() 42 | LINE = LINE.replace("\r", r'\r') 43 | LINE = "\r" + LINE + "\r" 44 | LINE = LINE.encode() 45 | self.serial_connection.write(LINE) 46 | sleep(sleep_time) 47 | # print(self.serial_connection.inWaiting()) 48 | while (self.serial_connection.inWaiting() > 0): 49 | response = response + self.serial_connection.read(self.serial_connection.inWaiting()) 50 | # print (response) 51 | response = re.sub('\r'.encode(), ''.encode(), response) 52 | sleep(sleep_time) 53 | response_list = response.split("\n".encode()) 54 | return response_list 55 | -------------------------------------------------------------------------------- /blink_led/serial_interface_upython.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import time 4 | from time import sleep 5 | import serial 6 | import re 7 | 8 | class SerialInterface(object): 9 | def __init__(self,port, baud): 10 | self.port = port 11 | self.baud = baud 12 | 13 | def connect_to_serial(self): 14 | # print ('Opening serial port...') 15 | self.serial_connection = serial.Serial(self.port, self.baud) 16 | if self.serial_connection.isOpen(): 17 | # print ('port opened!\n') 18 | return(True) 19 | else: 20 | return(False) 21 | 22 | def close_serial(self): 23 | self.serial_connection.close() 24 | 25 | def clean_file_sys(self): 26 | self.repl("import os",0.1) 27 | files = self.repl("os.listdir()", 0.4)[2] 28 | files = files.decode() 29 | files = files.strip('[]') 30 | files = files.split(',') 31 | for i in range(len(files)): 32 | files[i] = files[i].replace('\'','') 33 | files[i] = files[i].strip(' ') 34 | for file in files[:]: 35 | if file != 'boot.py': 36 | self.repl("os.remove('"+file+"')",0.4) 37 | 38 | def repl(self, LINE, sleep_time): 39 | response = '' 40 | response = response.encode() 41 | self.serial_connection.flushInput() 42 | LINE = LINE.replace("\r", r'\r') 43 | LINE = "\r" + LINE + "\r" 44 | LINE = LINE.encode() 45 | self.serial_connection.write(LINE) 46 | sleep(sleep_time) 47 | # print(self.serial_connection.inWaiting()) 48 | while (self.serial_connection.inWaiting() > 0): 49 | response = response + self.serial_connection.read(self.serial_connection.inWaiting()) 50 | # print (response) 51 | response = re.sub('\r'.encode(), ''.encode(), response) 52 | sleep(sleep_time) 53 | response_list = response.split("\n".encode()) 54 | return response_list 55 | -------------------------------------------------------------------------------- /template/serial_interface_upython.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import time 4 | from time import sleep 5 | import serial 6 | import re 7 | 8 | class SerialInterface(object): 9 | def __init__(self,port, baud): 10 | self.port = port 11 | self.baud = baud 12 | 13 | def connect_to_serial(self): 14 | # print ('Opening serial port...') 15 | self.serial_connection = serial.Serial(self.port, self.baud) 16 | if self.serial_connection.isOpen(): 17 | # print ('port opened!\n') 18 | return(True) 19 | else: 20 | return(False) 21 | 22 | def close_serial(self): 23 | self.serial_connection.close() 24 | 25 | def clean_file_sys(self): 26 | self.repl("import os",0.1) 27 | files = self.repl("os.listdir()", 0.4)[2] 28 | files = files.decode() 29 | files = files.strip('[]') 30 | files = files.split(',') 31 | for i in range(len(files)): 32 | files[i] = files[i].replace('\'','') 33 | files[i] = files[i].strip(' ') 34 | for file in files[:]: 35 | if file != 'boot.py': 36 | self.repl("os.remove('"+file+"')",0.4) 37 | 38 | def repl(self, LINE, sleep_time): 39 | response = '' 40 | response = response.encode() 41 | self.serial_connection.flushInput() 42 | LINE = LINE.replace("\r", r'\r') 43 | LINE = "\r" + LINE + "\r" 44 | LINE = LINE.encode() 45 | self.serial_connection.write(LINE) 46 | sleep(sleep_time) 47 | # print(self.serial_connection.inWaiting()) 48 | while (self.serial_connection.inWaiting() > 0): 49 | response = response + self.serial_connection.read(self.serial_connection.inWaiting()) 50 | # print (response) 51 | response = re.sub('\r'.encode(), ''.encode(), response) 52 | sleep(sleep_time) 53 | response_list = response.split("\n".encode()) 54 | return response_list 55 | -------------------------------------------------------------------------------- /conftime_DS3231/serial_interface_upython.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import time 4 | from time import sleep 5 | import serial 6 | import re 7 | 8 | class SerialInterface(object): 9 | def __init__(self,port, baud): 10 | self.port = port 11 | self.baud = baud 12 | 13 | def connect_to_serial(self): 14 | # print ('Opening serial port...') 15 | self.serial_connection = serial.Serial(self.port, self.baud) 16 | if self.serial_connection.isOpen(): 17 | # print ('port opened!\n') 18 | return(True) 19 | else: 20 | return(False) 21 | 22 | def close_serial(self): 23 | self.serial_connection.close() 24 | 25 | def clean_file_sys(self): 26 | self.repl("import os",0.1) 27 | files = self.repl("os.listdir()", 0.4)[2] 28 | files = files.decode() 29 | files = files.strip('[]') 30 | files = files.split(',') 31 | for i in range(len(files)): 32 | files[i] = files[i].replace('\'','') 33 | files[i] = files[i].strip(' ') 34 | for file in files[:]: 35 | if file != 'boot.py': 36 | self.repl("os.remove('"+file+"')",0.4) 37 | 38 | def repl(self, LINE, sleep_time): 39 | response = '' 40 | response = response.encode() 41 | self.serial_connection.flushInput() 42 | LINE = LINE.replace("\r", r'\r') 43 | LINE = "\r" + LINE + "\r" 44 | LINE = LINE.encode() 45 | self.serial_connection.write(LINE) 46 | sleep(sleep_time) 47 | # print(self.serial_connection.inWaiting()) 48 | while (self.serial_connection.inWaiting() > 0): 49 | response = response + self.serial_connection.read(self.serial_connection.inWaiting()) 50 | # print (response) 51 | response = re.sub('\r'.encode(), ''.encode(), response) 52 | sleep(sleep_time) 53 | response_list = response.split("\n".encode()) 54 | return response_list 55 | 56 | -------------------------------------------------------------------------------- /template/test_template.py: -------------------------------------------------------------------------------- 1 | # Do the serial interface between PC and DUT or DOUBLE 2 | from serial_interface_upython import SerialInterface 3 | # Library for testing with different asserts 4 | from should_dsl import should 5 | # Test class from wich our class inhereints 6 | import unittest 7 | # Operational System Interface 8 | import os 9 | import sys 10 | # Utils 11 | import time 12 | from time import sleep 13 | 14 | production_code = "dut_template.py" 15 | double_code = "double_template.py" 16 | build = "python -m mpy_cross -s -march=xtensa " 17 | DUT_PORT = "/dev/ttyUSB0" 18 | DOUBLE_PORT = "/dev/ttyUSB1" 19 | send = "ampy --port " 20 | # From set-up: 21 | # Building, connection and sending phase 22 | try: 23 | print("Building production code...") 24 | os.system(build+production_code) 25 | print("Building double code...") 26 | os.system(build+double_code) 27 | print("Cleaning the filesystem...") 28 | dut_serial = SerialInterface(DUT_PORT, 115200) 29 | dut_serial.connect_to_serial() 30 | dut_serial.clean_file_sys() 31 | dut_serial.close_serial() 32 | double_serial = SerialInterface(DOUBLE_PORT, 115200) 33 | double_serial.connect_to_serial() 34 | double_serial.clean_file_sys() 35 | double_serial.close_serial() 36 | print("Sending built production code...") 37 | os.system(send+DUT_PORT+" put "+production_code)#.replace(".py",".mpy")) 38 | print("Sending built double code...") 39 | os.system(send+DOUBLE_PORT+" put "+double_code)#.replace(".py",".mpy")) 40 | except: 41 | sys.exit('fail to upload file(s)') 42 | # Uncomment the next line for not to run the Test 43 | # sys.exit() 44 | 45 | # Testing Phase 46 | class Test_Template(unittest.TestCase): 47 | #Creates a serial connection and import the classes 48 | def setUp(self): 49 | print('\n') 50 | print("Connecting to DUT device...") 51 | self.dut_serial = SerialInterface(DUT_PORT, 115200) 52 | self.dut_serial.connect_to_serial() 53 | print("Connecting to DOUBLE device...") 54 | self.double_serial = SerialInterface(DOUBLE_PORT, 115200) 55 | self.double_serial.connect_to_serial() 56 | self.dut_serial.repl("from dut_template import Dut_class", 0.1) 57 | self.double_serial.repl("from double_template import Double_class", 0.1) 58 | 59 | # < Space for the test cases > 60 | 61 | #closes serial 62 | def tearDown(self): 63 | self.dut_serial.repl("del Dut_class", 0.2) 64 | self.double_serial.repl("del Double_class", 0.2) 65 | self.dut_serial.close_serial() 66 | self.double_serial.close_serial() 67 | 68 | if __name__ == '__main__': 69 | unittest.main() 70 | -------------------------------------------------------------------------------- /BLE/ble_temperature.py: -------------------------------------------------------------------------------- 1 | # THIRD PARTY CODE -> Original from https://github.com/micropython/micropython/tree/master/examples/bluetooth 2 | 3 | # This example demonstrates a simple temperature sensor peripheral. 4 | # 5 | # The sensor's local value updates every second, and it will notify 6 | # any connected central every 10 seconds. 7 | 8 | import bluetooth 9 | import random 10 | import struct 11 | import time 12 | from ble_advertising import advertising_payload 13 | 14 | from micropython import const 15 | _IRQ_CENTRAL_CONNECT = const(1 << 0) 16 | _IRQ_CENTRAL_DISCONNECT = const(1 << 1) 17 | 18 | # org.bluetooth.service.environmental_sensing 19 | _ENV_SENSE_UUID = bluetooth.UUID(0x181A) 20 | # org.bluetooth.characteristic.temperature 21 | _TEMP_CHAR = (bluetooth.UUID(0x2A6E), bluetooth.FLAG_READ|bluetooth.FLAG_NOTIFY,) 22 | _ENV_SENSE_SERVICE = (_ENV_SENSE_UUID, (_TEMP_CHAR,),) 23 | 24 | # org.bluetooth.characteristic.gap.appearance.xml 25 | _ADV_APPEARANCE_GENERIC_THERMOMETER = const(768) 26 | 27 | class BLETemperature: 28 | def __init__(self, ble, name='mpy-temp'): 29 | self._ble = ble 30 | self._ble.active(True) 31 | self._ble.irq(handler=self._irq) 32 | ((self._handle,),) = self._ble.gatts_register_services((_ENV_SENSE_SERVICE,)) 33 | self._connections = set() 34 | self._payload = advertising_payload(name=name, services=[_ENV_SENSE_UUID], appearance=_ADV_APPEARANCE_GENERIC_THERMOMETER) 35 | self._advertise() 36 | 37 | def _irq(self, event, data): 38 | # Track connections so we can send notifications. 39 | if event == _IRQ_CENTRAL_CONNECT: 40 | conn_handle, _, _, = data 41 | self._connections.add(conn_handle) 42 | elif event == _IRQ_CENTRAL_DISCONNECT: 43 | conn_handle, _, _, = data 44 | self._connections.remove(conn_handle) 45 | # Start advertising again to allow a new connection. 46 | self._advertise() 47 | 48 | def set_temperature(self, temp_deg_c, notify=False): 49 | # Data is sint16 in degrees Celsius with a resolution of 0.01 degrees Celsius. 50 | # Write the local value, ready for a central to read. 51 | self._ble.gatts_write(self._handle, struct.pack(' Original from https://github.com/micropython/micropython/tree/master/examples/bluetooth 2 | 3 | # Helpers for generating BLE advertising payloads. 4 | 5 | from micropython import const 6 | import struct 7 | import bluetooth 8 | 9 | # Advertising payloads are repeated packets of the following form: 10 | # 1 byte data length (N + 1) 11 | # 1 byte type (see constants below) 12 | # N bytes type-specific data 13 | 14 | _ADV_TYPE_FLAGS = const(0x01) 15 | _ADV_TYPE_NAME = const(0x09) 16 | _ADV_TYPE_UUID16_COMPLETE = const(0x3) 17 | _ADV_TYPE_UUID32_COMPLETE = const(0x5) 18 | _ADV_TYPE_UUID128_COMPLETE = const(0x7) 19 | _ADV_TYPE_UUID16_MORE = const(0x2) 20 | _ADV_TYPE_UUID32_MORE = const(0x4) 21 | _ADV_TYPE_UUID128_MORE = const(0x6) 22 | _ADV_TYPE_APPEARANCE = const(0x19) 23 | 24 | 25 | # Generate a payload to be passed to gap_advertise(adv_data=...). 26 | def advertising_payload(limited_disc=False, br_edr=False, name=None, services=None, appearance=0): 27 | payload = bytearray() 28 | 29 | def _append(adv_type, value): 30 | nonlocal payload 31 | payload += struct.pack('BB', len(value) + 1, adv_type) + value 32 | 33 | _append(_ADV_TYPE_FLAGS, struct.pack('B', (0x01 if limited_disc else 0x02) + (0x00 if br_edr else 0x04))) 34 | 35 | if name: 36 | _append(_ADV_TYPE_NAME, name) 37 | 38 | if services: 39 | for uuid in services: 40 | b = bytes(uuid) 41 | if len(b) == 2: 42 | _append(_ADV_TYPE_UUID16_COMPLETE, b) 43 | elif len(b) == 4: 44 | _append(_ADV_TYPE_UUID32_COMPLETE, b) 45 | elif len(b) == 16: 46 | _append(_ADV_TYPE_UUID128_COMPLETE, b) 47 | 48 | # See org.bluetooth.characteristic.gap.appearance.xml 49 | _append(_ADV_TYPE_APPEARANCE, struct.pack(' 6 | #include 7 | #include 8 | 9 | last_trans_info_t last_trans = {.recv_buffer_pointer = NULL, .size = 0}; 10 | 11 | mp_obj_t spi_slave_init(mp_uint_t n_args, const mp_obj_t *args) 12 | { 13 | int mosi, miso, sclk, cs, dma_channel; 14 | esp_err_t result; 15 | mosi = mp_obj_get_int(args[0]); 16 | miso = mp_obj_get_int(args[1]); 17 | sclk = mp_obj_get_int(args[2]); 18 | cs = mp_obj_get_int(args[3]); 19 | dma_channel = 0; 20 | 21 | //Configuration for the SPI bus 22 | spi_bus_config_t buscfg={ 23 | .mosi_io_num=mosi, 24 | .miso_io_num=miso, 25 | .sclk_io_num=sclk, 26 | .quadwp_io_num = -1, 27 | .quadhd_io_num = -1, 28 | }; 29 | 30 | //Configuration for the SPI slave interface 31 | spi_slave_interface_config_t slvcfg={ 32 | .mode=0, 33 | .spics_io_num=cs, 34 | .queue_size=1, 35 | .flags=0 36 | }; 37 | 38 | //Enable pull-ups on SPI lines so we don't detect rogue pulses when no master is connected. 39 | gpio_set_pull_mode(mosi, GPIO_PULLUP_ONLY); 40 | gpio_set_pull_mode(sclk, GPIO_PULLUP_ONLY); 41 | gpio_set_pull_mode(cs, GPIO_PULLUP_ONLY); 42 | 43 | //Initialize SPI slave interface 44 | result=spi_slave_initialize(HSPI_HOST, &buscfg, &slvcfg, dma_channel); 45 | if(result==ESP_OK) 46 | return mp_const_true; 47 | else 48 | return mp_const_false; 49 | } 50 | 51 | mp_obj_t spi_slave_free_bus() 52 | { 53 | esp_err_t result; 54 | // if(last_trans.recv_buffer_pointer != NULL) 55 | // free(last_trans.recv_buffer_pointer); 56 | result = spi_slave_free(HSPI_HOST); 57 | if(result==ESP_OK) 58 | return mp_const_true; 59 | else 60 | return mp_const_false; 61 | } 62 | 63 | mp_obj_t spi_slave_enable_transaction(mp_obj_t sendbuf_obj) 64 | { 65 | spi_slave_transaction_t transaction; 66 | esp_err_t result; 67 | mp_uint_t num_transfers; 68 | mp_obj_t *transfers_obj_array; 69 | mp_obj_get_array(sendbuf_obj, &num_transfers, &transfers_obj_array); 70 | uint8_t *sendbuf = (uint8_t*)malloc(num_transfers); 71 | uint8_t *recvbuf = (uint8_t*)malloc(num_transfers); 72 | uint8_t * sendbuf_aux = sendbuf; 73 | if(last_trans.recv_buffer_pointer != NULL) 74 | free(last_trans.recv_buffer_pointer); 75 | last_trans.recv_buffer_pointer = recvbuf; 76 | last_trans.size = num_transfers; 77 | for(int i = 0; i < num_transfers; ++i) 78 | { 79 | *sendbuf_aux = (uint8_t)mp_obj_get_int(*transfers_obj_array); 80 | sendbuf_aux++; 81 | transfers_obj_array++; 82 | } 83 | memset(&transaction, 0, sizeof(transaction)); 84 | transaction.length=num_transfers*8; 85 | transaction.tx_buffer=sendbuf; 86 | transaction.rx_buffer=recvbuf; 87 | result = spi_slave_transmit(HSPI_HOST, &transaction, portMAX_DELAY); 88 | if (result == ESP_OK) 89 | { 90 | printf("Transaction ok\n"); 91 | free(sendbuf); 92 | return mp_obj_new_bytearray(num_transfers, recvbuf); 93 | } 94 | else 95 | { 96 | printf("Transaction not ok"); 97 | return mp_const_false; 98 | } 99 | } 100 | 101 | // mp_obj_t spi_slave_enable_transaction(mp_obj_t sendbuf_obj, mp_obj_t recvbuf_obj) 102 | // { 103 | // spi_slave_transaction_t transaction; 104 | // esp_err_t result; 105 | 106 | // mp_buffer_info_t src; 107 | // mp_get_buffer_raise(sendbuf_obj, &src, MP_BUFFER_READ); 108 | // mp_buffer_info_t dest; 109 | // mp_get_buffer_raise(recvbuf_obj, &dest, MP_BUFFER_WRITE); 110 | // if (src.len != dest.len) { 111 | // mp_raise_ValueError("buffers must be the same length"); 112 | // } 113 | // memset(&transaction, 0, sizeof(transaction)); 114 | // transaction.length=src.len*8; 115 | // transaction.tx_buffer=src.buf; 116 | // transaction.rx_buffer=dest.buf; 117 | // result = spi_slave_transmit(HSPI_HOST, &transaction, portMAX_DELAY); 118 | // if (result == ESP_OK) 119 | // { 120 | // printf("Transaction aconteceu com sucesso\n"); 121 | // return mp_const_true; 122 | // } 123 | // else 124 | // { 125 | // printf("Transaction esmerdou"); 126 | // return mp_const_false; 127 | // } 128 | // } 129 | 130 | mp_obj_t spi_slave_get_received_buffer() 131 | { 132 | return mp_obj_new_bytearray(last_trans.size, last_trans.recv_buffer_pointer); 133 | } 134 | -------------------------------------------------------------------------------- /conftime_DS3231/double_DS3231.py: -------------------------------------------------------------------------------- 1 | import machine 2 | 3 | FREQUENCY_SCL = (400000) 4 | DS3231_I2C_ADDR = (0x68) 5 | DS3231_REG_SEC = (0x00) 6 | DS3231_REG_MIN = (0x01) 7 | DS3231_REG_HOUR = (0x02) 8 | DS3231_REG_WEEKDAY= (0x03) 9 | DS3231_REG_DAY = (0x04) 10 | DS3231_REG_MONTH = (0x05) 11 | DS3231_REG_YEAR = (0x06) 12 | 13 | class DOUBLE_DS3231(object): 14 | def __init__(self, sda, scl): 15 | self.sda_pin = sda 16 | self.scl_pin = scl 17 | self.i2c = machine.I2C(id = 1, mode=machine.I2C.SLAVE, speed=FREQUENCY_SCL, sda=self.sda_pin, scl=self.scl_pin, slave_addr=DS3231_I2C_ADDR) 18 | 19 | def DecToHex(self, dat): 20 | return (dat//10) * 16 + (dat%10) 21 | 22 | # When using this method the other methods such as Year(x), Hour(x) and the others 23 | # don't have the power to update the values, since the registers is mirroring the internal rtc value 24 | # So, the former way it's called dynamic set and the latter static set 25 | def use_internal_rtc(self,current_datetime=None): 26 | self.internal_rtc = machine.RTC() 27 | if current_datetime != None: 28 | self.set_current_time(current_datetime) 29 | else: 30 | current_datetime = (self.Year(), self.Month(), self.Day(), self.Hour(), self.Minute(), self.Second()) 31 | self.set_current_time(current_datetime) 32 | self.my_timer = machine.Timer(1) 33 | self.my_timer.init(period=1000,mode=self.my_timer.PERIODIC, callback=self.my_callback) 34 | 35 | def set_current_time(self, current_datetime): 36 | self.internal_rtc.init(current_datetime) 37 | 38 | def HexToDec(self, dat): 39 | return (dat//16) * 10 + (dat%16) 40 | 41 | def my_callback(self,timer): 42 | self.current_datetime = self.internal_rtc.now() 43 | self.i2c.setdata(chr(self.DecToHex(self.current_datetime[0]%100)), DS3231_REG_YEAR) 44 | self.i2c.setdata(chr(self.DecToHex(self.current_datetime[1])), DS3231_REG_MONTH) 45 | self.i2c.setdata(chr(self.DecToHex(self.current_datetime[2])), DS3231_REG_DAY) 46 | self.i2c.setdata(chr(self.DecToHex(self.current_datetime[3])), DS3231_REG_HOUR) 47 | self.i2c.setdata(chr(self.DecToHex(self.current_datetime[4])), DS3231_REG_MIN) 48 | self.i2c.setdata(chr(self.DecToHex(self.current_datetime[5])), DS3231_REG_SEC) 49 | #self.i2c.setdata(chr(self.DecToHex(self.current_datetime[6])), DS3231_REG_WEEKDAY) 50 | 51 | 52 | def Second(self, second = None): 53 | if second == None: 54 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_SEC, 1))) 55 | else: 56 | self.i2c.setdata(chr(self.DecToHex(second)), DS3231_REG_SEC) 57 | 58 | def Minute(self, minute = None): 59 | if minute == None: 60 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_MIN, 1))) 61 | else: 62 | self.i2c.setdata(chr(self.DecToHex(minute)), DS3231_REG_MIN) 63 | 64 | def Hour(self, hour = None): 65 | if hour == None: 66 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_HOUR, 1))) 67 | else: 68 | self.i2c.setdata(chr(self.DecToHex(hour)), DS3231_REG_HOUR) 69 | 70 | def Time(self, dat = None): 71 | if dat == None: 72 | return [self.Hour(), self.Minute(), self.Second()] 73 | else: 74 | self.Hour(dat[0]) 75 | self.Minute(dat[1]) 76 | self.Second(dat[2]) 77 | 78 | def Weekday(self, weekday = None): 79 | if weekday == None: 80 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_WEEKDAY, 1))) 81 | else: 82 | self.i2c.setdata(chr(self.DecToHex(weekday)), DS3231_REG_WEEKDAY) 83 | 84 | def Day(self, day = None): 85 | if day == None: 86 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_DAY, 1))) 87 | else: 88 | self.i2c.setdata(chr(self.DecToHex(day)), DS3231_REG_DAY) 89 | 90 | def Month(self, month = None): 91 | if month == None: 92 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_MONTH, 1))) 93 | else: 94 | self.i2c.setdata(chr(self.DecToHex(month)), DS3231_REG_MONTH) 95 | 96 | def Year(self, year = None): 97 | if year == None: 98 | return self.HexToDec(ord(self.i2c.getdata(DS3231_REG_YEAR, 1)))+2000 99 | else: 100 | self.i2c.setdata(chr(self.DecToHex(year%100)), DS3231_REG_YEAR) 101 | 102 | def Date(self, dat = None): 103 | if dat == None: 104 | return [self.Year(), self.Month(), self.Day()] 105 | else: 106 | self.Year(dat[0]) 107 | self.Month(dat[1]) 108 | self.Day(dat[2]) 109 | 110 | def DateTime(self, dat = None): 111 | if dat == None: 112 | return self.Date() + [self.Weekday()] + self.Time() 113 | else: 114 | self.Year(dat[0]) 115 | self.Month(dat[1]) 116 | self.Day(dat[2]) 117 | self.Weekday(dat[3]) 118 | self.Hour(dat[4]) 119 | self.Minute(dat[5]) 120 | self.Second(dat[6]) 121 | 122 | def deinit(self): 123 | self.i2c.deinit() 124 | if hasattr(self, 'my_timer'): 125 | self.my_timer.deinit() 126 | 127 | 128 | -------------------------------------------------------------------------------- /BLE/test_sensor_cellphone.py: -------------------------------------------------------------------------------- 1 | # Do the serial interface between PC and DUT or DOUBLE 2 | from serial_interface_upython import SerialInterface 3 | # Library for testing with different asserts 4 | from should_dsl import should 5 | # Test class from wich our class inhereints 6 | import unittest 7 | # Operational System Interface 8 | import os 9 | import sys 10 | # Utils 11 | import time 12 | from time import sleep 13 | 14 | production_code = "dut_sensor.py" 15 | double_code = "double_cellphone.py" 16 | auxiliary_double_codes = ["ble_advertising.py", "ble_temperature_central.py"] 17 | auxiliary_dut_codes = ["ble_advertising.py", "ble_temperature.py"] 18 | build = "python -m mpy_cross -s -march=xtensa " 19 | DUT_PORT = "/dev/ttyUSB0" 20 | DOUBLE_PORT = "/dev/ttyUSB1" 21 | send = "ampy --port " 22 | # From set-up: 23 | # Building, connection and sending phase 24 | try: 25 | print("Building production code...") 26 | os.system(build+production_code) 27 | print("Building double code...") 28 | os.system(build+double_code) 29 | print("Cleaning DUT's filesystem...") 30 | dut_serial = SerialInterface(DUT_PORT, 115200) 31 | dut_serial.connect_to_serial() 32 | dut_serial.clean_file_sys() 33 | dut_serial.close_serial() 34 | print("Cleaning DOUBLE's filesystem...") 35 | double_serial = SerialInterface(DOUBLE_PORT, 115200) 36 | double_serial.connect_to_serial() 37 | double_serial.clean_file_sys() 38 | double_serial.close_serial() 39 | print("Sending built production code...") 40 | os.system(send+DUT_PORT+" put "+production_code)#.replace(".py",".mpy")) 41 | print("Sending auxiliary production codes...") 42 | for code in auxiliary_dut_codes: 43 | os.system(send+DUT_PORT+" put "+code) 44 | print("Sending built double code...") 45 | os.system(send+DOUBLE_PORT+" put "+double_code)#.replace(".py",".mpy")) 46 | print("Sending auxiliary double codes...") 47 | for code in auxiliary_double_codes: 48 | os.system(send+DOUBLE_PORT+" put "+code) 49 | time.sleep(5) 50 | except: 51 | sys.exit('fail to upload file(s)') 52 | # Uncomment the next line for not to run the Test 53 | # sys.exit() 54 | # Testing Phase 55 | class Test_BLE(unittest.TestCase): 56 | #Creates a serial connection and import the classes 57 | def setUp(self): 58 | print('\n') 59 | print("Connecting to DUT device...") 60 | self.dut_serial = SerialInterface(DUT_PORT, 115200) 61 | self.dut_serial.connect_to_serial() 62 | print("Connecting to DOUBLE device...") 63 | self.double_serial = SerialInterface(DOUBLE_PORT, 115200) 64 | self.double_serial.connect_to_serial() 65 | self.dut_serial.repl("from dut_sensor import BLE_Sensor", 0.2) 66 | self.double_serial.repl("from double_cellphone import DOUBLE_cellphone", 0.2) 67 | 68 | def test_connection(self): 69 | print("Testing if the dut can connect properly to a central") 70 | advertising_name = "my_sensor" 71 | # 1 - Objects Creation and Input Injection 72 | self.dut_serial.repl("sensor = BLE_Sensor(\""+advertising_name+"\")", 0.2) 73 | self.double_serial.repl("cellphone = DOUBLE_cellphone()", 0.2) 74 | time.sleep(5) 75 | # 3 - Result Gathering 76 | connection = self.double_serial.repl("cellphone.check_connectivity()", 0.2)[2] 77 | connection = connection.decode() 78 | print("Connection Result", connection) 79 | connection |should| contain (str(True)) 80 | 81 | def test_read(self): 82 | print("Testing reading a value from the dut") 83 | advertising_name = "my_sensor" 84 | expected_value = 25 85 | # 1 - Objects Creation and Input Injection 86 | self.dut_serial.repl("sensor = BLE_Sensor(\""+advertising_name+"\")", 0.2) 87 | self.double_serial.repl("cellphone = DOUBLE_cellphone()", 0.2) 88 | time.sleep(5) 89 | # 2 - Input Injection 90 | self.dut_serial.repl("sensor.set_value("+str(expected_value)+")", 0.2) 91 | self.double_serial.repl("cellphone.issue_reading()", 0.2) 92 | # 3 - Result Gathering 93 | time.sleep(1) 94 | gotten_value = self.double_serial.repl("cellphone.read_value()", 0.2)[2] 95 | gotten_value = gotten_value.decode() 96 | print("Expected value", expected_value,"Read value", gotten_value) 97 | gotten_value |should| contain (str(expected_value)) 98 | 99 | def test_notify(self): 100 | print("Testing the notification") 101 | advertising_name = "my_sensor" 102 | expected_value = 20 103 | # 1 - Objects Creation and Input Injection 104 | self.dut_serial.repl("sensor = BLE_Sensor(\""+advertising_name+"\")", 0.2) 105 | self.double_serial.repl("cellphone = DOUBLE_cellphone()", 0.2) 106 | time.sleep(5) 107 | # 2 - Input Injection 108 | self.dut_serial.repl("sensor.set_value("+str(expected_value)+", True)", 0.2) 109 | # 3 - Result Gathering 110 | time.sleep(1) 111 | gotten_value = self.double_serial.repl("cellphone.read_value()", 0.2)[2] 112 | gotten_value = gotten_value.decode() 113 | print("Notified value", expected_value, "Read value", gotten_value) 114 | gotten_value |should| contain (str(expected_value)) 115 | 116 | #closes serial 117 | def tearDown(self): 118 | self.double_serial.repl("cellphone.deinit();del cellphone; del DOUBLE_cellphone;", 0.2) 119 | self.dut_serial.repl("sensor.deinit();del sensor; del BLE_Sensor", 0.2) 120 | self.dut_serial.close_serial() 121 | self.double_serial.close_serial() 122 | time.sleep(12) 123 | 124 | if __name__ == '__main__': 125 | unittest.main() 126 | -------------------------------------------------------------------------------- /conftime_DS3231/DS3231.py: -------------------------------------------------------------------------------- 1 | ''' 2 | DS3231 RTC drive 3 | 4 | Author: shaoziyang 5 | Date: 2018.3 6 | 7 | http://www.micropython.org.cn 8 | ''' 9 | from machine import I2C, Pin 10 | 11 | DS3231_I2C_ADDR = (0x68) 12 | DS3231_REG_SEC = (0x00) 13 | DS3231_REG_MIN = (0x01) 14 | DS3231_REG_HOUR = (0x02) 15 | DS3231_REG_WEEKDAY= (0x03) 16 | DS3231_REG_DAY = (0x04) 17 | DS3231_REG_MONTH = (0x05) 18 | DS3231_REG_YEAR = (0x06) 19 | DS3231_REG_A1SEC = (0x07) 20 | DS3231_REG_A1MIN = (0x08) 21 | DS3231_REG_A1HOUR = (0x09) 22 | DS3231_REG_A1DAY = (0x0A) 23 | DS3231_REG_A2MIN = (0x0B) 24 | DS3231_REG_A2HOUR = (0x0C) 25 | DS3231_REG_A2DAY = (0x0D) 26 | DS3231_REG_CTRL = (0x0E) 27 | DS3231_REG_STA = (0x0F) 28 | DS3231_REG_AGOFF = (0x10) 29 | DS3231_REG_TEMP = (0x11) 30 | 31 | PER_DISABLE = (0) 32 | PER_MINUTE = (1) 33 | PER_HOUR = (2) 34 | PER_DAY = (3) 35 | PER_WEEKDAY = (4) 36 | PER_MONTH = (5) 37 | 38 | class DS3231(): 39 | def __init__(self, i2c): 40 | self.i2c = i2c 41 | self.setReg(DS3231_REG_CTRL, 0x4C) 42 | 43 | def DecToHex(self, dat): 44 | return (dat//10) * 16 + (dat%10) 45 | 46 | def HexToDec(self, dat): 47 | return (dat//16) * 10 + (dat%16) 48 | 49 | def setReg(self, reg, dat): 50 | self.i2c.writeto(DS3231_I2C_ADDR, bytearray([reg, dat])) 51 | 52 | def getReg(self, reg): 53 | self.i2c.writeto(DS3231_I2C_ADDR, bytearray([reg])) 54 | return self.i2c.readfrom(DS3231_I2C_ADDR, 1)[0] 55 | 56 | def Second(self, second = None): 57 | if second == None: 58 | return self.HexToDec(self.getReg(DS3231_REG_SEC)) 59 | else: 60 | self.setReg(DS3231_REG_SEC, self.DecToHex(second%60)) 61 | 62 | def Minute(self, minute = None): 63 | if minute == None: 64 | return self.HexToDec(self.getReg(DS3231_REG_MIN)) 65 | else: 66 | self.setReg(DS3231_REG_MIN, self.DecToHex(minute%60)) 67 | 68 | def Hour(self, hour = None): 69 | if hour == None: 70 | return self.HexToDec(self.getReg(DS3231_REG_HOUR)) 71 | else: 72 | self.setReg(DS3231_REG_HOUR, self.DecToHex(hour%24)) 73 | 74 | def Weekday(self, weekday = None): 75 | if weekday == None: 76 | return self.HexToDec(self.getReg(DS3231_REG_WEEKDAY)) 77 | else: 78 | self.setReg(DS3231_REG_WEEKDAY, self.DecToHex(weekday%8)) 79 | 80 | def Day(self, day = None): 81 | if day == None: 82 | return self.HexToDec(self.getReg(DS3231_REG_DAY)) 83 | else: 84 | self.setReg(DS3231_REG_DAY, self.DecToHex(day%32)) 85 | 86 | def Month(self, month = None): 87 | if month == None: 88 | return self.HexToDec(self.getReg(DS3231_REG_MONTH)) 89 | else: 90 | self.setReg(DS3231_REG_MONTH, self.DecToHex(month%13)) 91 | 92 | def Year(self, year = None): 93 | if year == None: 94 | return self.HexToDec(self.getReg(DS3231_REG_YEAR)) + 2000 95 | else: 96 | self.setReg(DS3231_REG_YEAR, self.DecToHex(year%100)) 97 | 98 | def Date(self, dat = None): 99 | if dat == None: 100 | return [self.Year(), self.Month(), self.Day()] 101 | else: 102 | self.Year(dat[0]%100) 103 | self.Month(dat[1]%13) 104 | self.Day(dat[2]%32) 105 | 106 | def Time(self, dat = None): 107 | if dat == None: 108 | return [self.Hour(), self.Minute(), self.Second()] 109 | else: 110 | self.Hour(dat[0]%24) 111 | self.Minute(dat[1]%60) 112 | self.Second(dat[2]%60) 113 | 114 | def DateTime(self, dat = None): 115 | if dat == None: 116 | return self.Date() + [self.Weekday()] + self.Time() 117 | else: 118 | self.Year(dat[0]) 119 | self.Month(dat[1]) 120 | self.Day(dat[2]) 121 | self.Weekday(dat[3]) 122 | self.Hour(dat[4]) 123 | self.Minute(dat[5]) 124 | self.Second(dat[6]) 125 | 126 | def ALARM(self, day, hour, minute, repeat): 127 | IE = self.getReg(DS3231_REG_CTRL) 128 | if repeat == PER_DISABLE: 129 | self.setReg(DS3231_REG_CTRL, IE & 0xFC) # disable ALARM OUT 130 | return 131 | IE |= 0x46 132 | self.setReg(DS3231_REG_CTRL, IE) 133 | M2 = M3 = M4 = 0x80 134 | DT = 0 135 | if repeat == PER_MINUTE: 136 | pass 137 | elif repeat == PER_HOUR: 138 | M2 = 0 139 | elif repeat == PER_DAY: 140 | M2 = M3 = 0 141 | else: 142 | M2 = M3 = M4 = 0 143 | if repeat == PER_WEEKDAY: 144 | DT = 0x40 145 | self.setReg(DS3231_REG_A2MIN, self.DecToHex(minute%60)|M2) 146 | self.setReg(DS3231_REG_A2HOUR, self.DecToHex(hour%24)|M3) 147 | self.setReg(DS3231_REG_A2DAY, self.DecToHex(day%32)|M4|DT) 148 | 149 | def ClearALARM(self): 150 | self.setReg(DS3231_REG_STA, 0) 151 | 152 | def Temperature(self): 153 | t1 = self.getReg(DS3231_REG_TEMP) 154 | t2 = self.getReg(DS3231_REG_TEMP + 1) 155 | if t1>0x7F: 156 | return t1 - t2/256 -256 157 | else: 158 | return t1 + t2/256 159 | -------------------------------------------------------------------------------- /GPS/test_positioning_GPS.py: -------------------------------------------------------------------------------- 1 | # Do the serial interface between PC and DUT or DOUBLE 2 | from serial_interface_upython import SerialInterface 3 | # Library for testing with different asserts 4 | from should_dsl import should 5 | # Test class from wich our class inhereints 6 | import unittest 7 | # Operational System Interface 8 | import os 9 | import sys 10 | # Utils 11 | import time 12 | from time import sleep 13 | 14 | production_code = "dut_positioning.py" 15 | double_code = "double_GPS.py" 16 | auxiliar_code = "adafruit_gps.py" 17 | build = "python -m mpy_cross -s -march=xtensa " 18 | DUT_PORT = "/dev/ttyUSB0" 19 | DOUBLE_PORT = "/dev/ttyUSB1" 20 | send = "ampy --port " 21 | # From set-up: 22 | # Building, connection and sending phase 23 | try: 24 | print("Building production code...") 25 | os.system(build+production_code) 26 | print("Building double code...") 27 | os.system(build+double_code) 28 | print("Building auxiliar code...") 29 | os.system(build+auxiliar_code) 30 | print("Cleaning the filesystem...") 31 | dut_serial = SerialInterface(DUT_PORT, 115200) 32 | dut_serial.connect_to_serial() 33 | dut_serial.clean_file_sys() 34 | dut_serial.close_serial() 35 | double_serial = SerialInterface(DOUBLE_PORT, 115200) 36 | double_serial.connect_to_serial() 37 | double_serial.clean_file_sys() 38 | double_serial.close_serial() 39 | print("Sending built production code...") 40 | os.system(send+DUT_PORT+" put "+production_code)#.replace(".py",".mpy")) 41 | print("Sending built auxiliar_code...") 42 | os.system(send+DUT_PORT+" put "+auxiliar_code)#.replace(".py",".mpy")) 43 | os.system(send+DOUBLE_PORT+" put "+double_code)#.replace(".py",".mpy")) 44 | except: 45 | sys.exit('fail in set-up phase') 46 | # Uncomment the next line for not to run the Test 47 | # sys.exit() 48 | 49 | # Testing Phase 50 | class Test_Template(unittest.TestCase): 51 | #Creates a serial connection and import the classes 52 | def setUp(self): 53 | print('\n') 54 | print("Connecting to DUT device...") 55 | self.dut_serial = SerialInterface(DUT_PORT, 115200) 56 | self.dut_serial.connect_to_serial() 57 | print("Connecting to DOUBLE device...") 58 | self.double_serial = SerialInterface(DOUBLE_PORT, 115200) 59 | self.double_serial.connect_to_serial() 60 | self.dut_serial.repl("from dut_positioning import Positioning", 0.1) 61 | self.double_serial.repl("from double_GPS import DOUBLE_GPS", 0.1) 62 | 63 | def test_send_command_configuration(self): 64 | print("\nTesting the method send_command() configuring GPS to send GGA and RMC info") 65 | expected_command = 'PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0' 66 | print("Expected command: "+expected_command) 67 | # 1 - Objects Creation 68 | self.double_serial.repl("gps = DOUBLE_GPS(22,16,2)",0.2) 69 | self.dut_serial.repl("tracker = Positioning(17,16,2)",0.2) 70 | # 2 - Input Injection 71 | self.dut_serial.repl("tracker.send_command('"+expected_command+"')", 0.2) 72 | # 3 - Results gathering 73 | gotten_command = self.double_serial.repl("gps.received_command()",0.2)[2] 74 | # 4 - Assertion 75 | gotten_command = gotten_command.decode() 76 | gotten_command = gotten_command.replace('\'','') 77 | print("Gotten command: "+gotten_command) 78 | gotten_command |should| equal_to (expected_command) 79 | 80 | def test_send_command_update_rate(self): 81 | print("\nTesting the method send_command() updating GPS rate to 1 second") 82 | command = 'PMTK220,1000' 83 | expected_answer = '$GPRMC,141623.523,A,2143.963,S,04111.493,W,,,301019,000.0,W*7B\n' 84 | print("Expected answer: "+expected_answer) 85 | # 1 - Objects Creation 86 | self.double_serial.repl("gps = DOUBLE_GPS(22,16,2)",0.2) 87 | self.dut_serial.repl("tracker = Positioning(17,16,2)",0.2) 88 | # 2 - Input Injection 89 | self.dut_serial.repl("tracker.send_command('"+command+"')", 0.2) 90 | self.double_serial.repl("gps.received_command()",0.2) 91 | sleep(1) 92 | # 3 - Results gathering 93 | gotten_answer = self.dut_serial.repl("tracker.received_command()",0.2)[2] 94 | # 4 - Assertion 95 | gotten_answer = gotten_answer.decode() # To transform from array bytes to String 96 | gotten_answer = gotten_answer[1:] # To ignore the first char 97 | gotten_answer = gotten_answer.replace('\'','') # To replace the char (') 98 | gotten_answer = gotten_answer.replace('\\n','\n') 99 | print("Gotten answer: "+gotten_answer) 100 | gotten_answer |should| equal_to (expected_answer) 101 | 102 | def test_get_latitude(self): 103 | print("\nTesting the method get_latitude()") 104 | expected_latitude = -21.732717 105 | print("Expected answer: "+str(expected_latitude)) 106 | # 1 - Objects Creation 107 | self.double_serial.repl("gps = DOUBLE_GPS(22,16,2)",0.2) 108 | self.dut_serial.repl("tracker = Positioning(17,16,2)",0.2) 109 | # 2 - Input Injection 110 | self.dut_serial.repl("tracker.send_command('PMTK220,1000')", 0.2) 111 | self.double_serial.repl("gps.received_command()",0.2) 112 | sleep(1) 113 | # 3 - Results gathering 114 | gotten_answer = self.dut_serial.repl("tracker.get_latitude()",0.2)[2] 115 | # 4 - Assertion 116 | gotten_answer = gotten_answer.decode() # To transform from array bytes to String 117 | gotten_answer = float(gotten_answer) 118 | print("Gotten answer: "+str(gotten_answer)) 119 | gotten_answer |should| close_to(expected_latitude, delta=0.000005) 120 | 121 | #Closes serial 122 | def tearDown(self): 123 | # 5 Descomissioning 124 | self.double_serial.repl("gps.deinit(); del gps; del DOUBLE_GPS",0.2) 125 | self.dut_serial.repl("tracker.deinit(); del tracker; del Positioning",0.2) 126 | self.dut_serial.close_serial() 127 | self.double_serial.close_serial() 128 | pass 129 | 130 | if __name__ == '__main__': 131 | unittest.main() 132 | -------------------------------------------------------------------------------- /SPI/README.md: -------------------------------------------------------------------------------- 1 | # SPI slave mode for ESP32 2 | 3 | The original micropython firmware does not support spi in the slave mode on esp32. So this module was created to allow developing test cases to verify 4 | a production code that uses the SPI in the master mode. 5 | You can use the new functionality in two ways: 6 | * Building your own firmware along with the extra module that is available on `mymodules/spi_slave/` dir. The instructions to build are in the next section "SPI module". 7 | * Or you can simply get the pre-built-firmware on `pre-built-firmware/` dir. The instructions to upload it is in the next section "Pre Built Firmware with support for SPI slave mode". 8 | 9 | ## SPI Module 10 | 11 | This is the extra module for micropython that intended to expose the spi slave driver's basic functionality for esp32. 12 | 13 | After too many tests this module was considered unstable, it was tested with and without DMA, with and without Tasks and the spi slave driver has been shown unstable in all conditions. The esp-IDF version used was v 3.3. The micropython version used was v 1.11. 14 | 15 | Considering you have configured the ESP-IDF toolchain and cloned the micropython repository, to build and to embed the module into the firmware you should run the following command: 16 | 17 | make USER_C_MODULES=../../../mymodules CFLAGS_EXTRA=-DMODULE_SPI_SLAVE_ENABLED=1 all PYTHON=python2 18 | 19 | Considering that the micropython directory was side by side to mymodules directory. 20 | 21 | --micropython/ 22 | 23 | --mymodules/ 24 | 25 | The command was run in the ports/esp32/ directory. 26 | 27 | After running this command, just run `make deploy` to upload the newly built firmware. This command uses by standard the `/dev/ttyUSB0` port. If your device is using another port, it should be passed as a parameter. The full documentation is at micropython's official repository. 28 | 29 | To use this module from inside the repl in the esp32: 30 | 31 | import spi_slave 32 | 33 | This module offers the following API: 34 | 35 | * `spi_slave.init(mosi_pin, miso_pin, sclk_pin, cs_pin)` 36 | 37 | This function initializes the spi bus on the slave side according to the params given. The params are int numbers, they are all proper initialized inside the function. 38 | This function returns false for failure or true for success. 39 | 40 | 41 | * `spi_slave.free_bus()` 42 | 43 | This function deinitializes the bus, allowing other slaves to communicate with the master. It returns false for failure and true for success. 44 | 45 | * `spi_slave.enable_transaction(list)` 46 | 47 | This function lets a transaction prepared for when the master starts a transaction. So the param is a list containing all the elements to be placed at the send buffer. For example: spi_slave.enable_transaction([1,2,3]). This is currently a blocking function, which means it will only release the repl when the transaction gets over, and it returns false for fail and returns the received buffer in a byte array format in the case of success. 48 | 49 | * `spi_slave.get_received_buffer()` 50 | 51 | This function returns the last transaction received buffer (byte array format). 52 | 53 | Special thanks to Zoltán Vörös for this helpful discussion and for the most complete guide to starting building my own module: 54 | https://github.com/v923z/micropython-usermod/issues/3 55 | https://micropython-usermod.readthedocs.io/en/latest/usermods_01.html 56 | 57 | ## Pre Built Firmware with support for SPI slave mode 58 | 59 | This a ready-to-use pre-built firmware with support for SPI in the slave mode. Using this module it is not necessary to build the whole firmware. You only need to use esptool to upload it. 60 | 61 | First, erase the flash with the following command: 62 | 63 | esptool.py --port /dev/ttyUSB0 erase_flash 64 | 65 | Then, after erasing, just upload the firmware with the following command: 66 | 67 | esptool.py --chip esp32 --port /dev/ttyUSB1 --baud 460800 write_flash -z 0x1000 firmware.bin 68 | 69 | P.S: make sure you have esptool installed. 70 | You may check if everything is ok opening the repl using picocom: 71 | picocom /dev/ttyUSB0 -b115200 72 | 73 | 74 | Remember: this firmware is only for the double, the DUT remains with the original firmware. 75 | 76 | ## Example on how to use it 77 | 78 | * Slave side 79 | ```python 80 | import spi_slave; 81 | spi_slave.init(13,12,14,15); 82 | tx = bytearray('hi master') 83 | tx = list(tx) 84 | spi_slave.enable_transaction(tx) 85 | spi_slave.get_received_buffer() 86 | ``` 87 | * Master side 88 | ```python 89 | from machine import Pin, SPI; 90 | spi_master = SPI(1, baudrate=1000000,polarity=0, phase=0, bits=8, firstbit=0, sck=Pin(14), mosi=Pin(13), miso=Pin(12)); 91 | cs = Pin(15, Pin.OUT); 92 | tx = bytearray('hi slave!') 93 | rx = bytearray(len(tx)) 94 | cs.off() 95 | spi_master.write_readinto(tx,rx) 96 | cs.on() 97 | rx #it will show the received result 98 | ``` 99 | Try it: Just paste the snippets on the repl. First the slave, after the master. Or try to run step-by-step. 100 | 101 | # SPI Demo 102 | 103 | This example shows how to test sending and receiving data on the SPI bus. The DOUBLE is playing the role of an SPI slave as any peripheral that uses SPI to talk to a microcontroller. 104 | 105 | ## Firmwares 106 | DUT: [micropython original firmware](http://micropython.org/download#esp32). 107 | 108 | DOUBLE: [micropython with spi slave mode](https://github.com/saramonteiro/micropython_test_lib/tree/master/SPI/pre-built-firmware). 109 | 110 | ## How to run it: 111 | ``` 112 | python3 test_master_slave.py -v 113 | ``` 114 | 115 | ## Electrical Connections 116 | 117 | | | DUT | DOUBLE 118 | ---- | ---- | ---- 119 | MOSI | 13 | 13 120 | MISO | 12 | 12 121 | SCLK | 14 | 14 122 | CS | 15 | 15 123 | 124 | 125 | 126 | 127 | -------------------------------------------------------------------------------- /SPI/test_master_slave.py: -------------------------------------------------------------------------------- 1 | # Do the serial interface between PC and DUT or DOUBLE 2 | from serial_interface_upython import SerialInterface 3 | # Library for testing with different asserts 4 | from should_dsl import should 5 | # Test class from wich our class inhereints 6 | import unittest 7 | # Operational System Interface 8 | import os 9 | import sys 10 | # Utils 11 | import time 12 | from time import sleep 13 | 14 | production_code = "dut_master.py" 15 | double_code = "double_slave.py" 16 | build = "python -m mpy_cross -s -march=xtensa " 17 | DUT_PORT = "/dev/ttyUSB0" 18 | DOUBLE_PORT = "/dev/ttyUSB1" 19 | send = "ampy --port " 20 | # From set-up: 21 | # Building, connection and sending phase 22 | try: 23 | print("Building production code...") 24 | os.system(build+production_code) 25 | print("Building double code...") 26 | os.system(build+double_code) 27 | print("Cleaning the filesystem...") 28 | dut_serial = SerialInterface(DUT_PORT, 115200) 29 | dut_serial.connect_to_serial() 30 | dut_serial.clean_file_sys() 31 | dut_serial.close_serial() 32 | double_serial = SerialInterface(DOUBLE_PORT, 115200) 33 | double_serial.connect_to_serial() 34 | double_serial.clean_file_sys() 35 | double_serial.close_serial() 36 | print("Sending built production code...") 37 | os.system(send+DUT_PORT+" put "+production_code)#.replace(".py",".mpy")) 38 | print("Sending built double code...") 39 | os.system(send+DOUBLE_PORT+" put "+double_code)#.replace(".py",".mpy")) 40 | except: 41 | sys.exit('fail to upload file(s)') 42 | # Uncomment the next line for not to run the Test 43 | # sys.exit() 44 | 45 | # Testing Phase 46 | class Test_Template(unittest.TestCase): 47 | #Creates a serial connection and import the classes 48 | def setUp(self): 49 | print('\n') 50 | print("Connecting to DUT device...") 51 | self.dut_serial = SerialInterface(DUT_PORT, 115200) 52 | self.dut_serial.connect_to_serial() 53 | print("Connecting to DOUBLE device...") 54 | self.double_serial = SerialInterface(DOUBLE_PORT, 115200) 55 | self.double_serial.connect_to_serial() 56 | self.dut_serial.repl("from dut_master import Dut_master", 0.1) 57 | self.double_serial.repl("from double_slave import Double_slave", 0.1) 58 | 59 | 60 | def test_reading_registers_without_indicating_address(self): 61 | print("\nTesting the method read_registers_wo_address()") 62 | expected_readings = [1,2,3] 63 | gotten_readings = [] 64 | print("Expected Readings "+str(expected_readings)) 65 | # 1 - Objects Creation 66 | self.double_serial.repl("slave = Double_slave(13,12,14,15)",0.2) 67 | self.dut_serial.repl("master = Dut_master(13,12,14,15)",0.2) 68 | # 2 - Input Injection 69 | self.double_serial.repl("slave.enable_transaction("+str(expected_readings)+")",0.2) 70 | # 3 - Results gathering 71 | gotten_readings = self.dut_serial.repl("master.read_registers_wo_address(3)",0.2)[2] 72 | gotten_readings = gotten_readings.decode() 73 | # 4 - Assertion 74 | print("Gotten value: "+gotten_readings) 75 | gotten_readings |should| equal_to (str(expected_readings)) 76 | 77 | def test_reading_registers_indicating_address(self): 78 | print("\nTesting the method read_registers_w_address()") 79 | expected_readings = [1,2,3] 80 | expected_written = [14,0,0,0] 81 | gotten_readings = [] 82 | print("Expected Readings "+str(expected_readings)) 83 | # 1 - Objects Creation 84 | self.double_serial.repl("slave = Double_slave(13,12,14,15)",0.2) 85 | self.dut_serial.repl("master = Dut_master(13,12,14,15)",0.2) 86 | # 2 - Input Injection 87 | self.double_serial.repl("slave.enable_transaction([0,1,2,3])",0.2) 88 | # 3 - Results gathering 89 | gotten_readings = self.dut_serial.repl("master.read_registers_w_address(14,3)",0.2)[2] 90 | gotten_readings = gotten_readings.decode() 91 | gotten_written = self.double_serial.repl("slave.get_received_buffer()",0.2)[2] 92 | gotten_written = gotten_written.decode() 93 | # 4 - Assertion 94 | print("Gotten value: "+gotten_readings) 95 | gotten_readings |should| equal_to (str(expected_readings)) 96 | gotten_written |should| equal_to (str(expected_written)) 97 | 98 | def test_writing_registers_without_indicating_address(self): 99 | print("\nTesting the method write_registers_wo_address()") 100 | expected_written = [1,2,3] 101 | gotten_values = [] 102 | print("Expected written values "+str(expected_written)) 103 | # 1 - Objects Creation 104 | self.double_serial.repl("slave = Double_slave(13,12,14,15)",0.2) 105 | self.dut_serial.repl("master = Dut_master(13,12,14,15)",0.2) 106 | # 2 - Input Injection 107 | self.double_serial.repl("slave.enable_transaction([0,0,0])",0.2) 108 | self.dut_serial.repl("master.write_registers_wo_address("+str(expected_written)+")",0.2) 109 | # 3 - Results gathering 110 | gotten_values = self.double_serial.repl("slave.get_received_buffer()", 0.2)[2] 111 | gotten_values = gotten_values.decode() 112 | # 4 - Assertion 113 | print("Gotten value: "+gotten_values) 114 | gotten_values |should| equal_to (str(expected_written)) 115 | 116 | def test_writing_registers_indicating_address(self): 117 | print("\nTesting the method write_registers_w_address()") 118 | expected_written = [1,2,3] 119 | address = 14 120 | gotten_values = [] 121 | print("Expected written values "+str(expected_written)) 122 | # 1 - Objects Creation 123 | self.double_serial.repl("slave = Double_slave(13,12,14,15)",0.2) 124 | self.dut_serial.repl("master = Dut_master(13,12,14,15)",0.2) 125 | # 2 - Input Injection 126 | self.double_serial.repl("slave.enable_transaction([0,0,0,0])",0.2) 127 | self.dut_serial.repl("master.write_registers_w_address("+str(address)+","+str(expected_written)+")",0.2) 128 | # 3 - Results gathering 129 | gotten_values = self.double_serial.repl("slave.get_received_buffer()",0.2)[2] 130 | gotten_values = gotten_values.decode() 131 | # 4 - Assertion 132 | print("Gotten value: "+gotten_values) 133 | expected_written.insert(0,address) 134 | gotten_values |should| equal_to (str(expected_written)) 135 | 136 | #closes serial 137 | def tearDown(self): 138 | self.dut_serial.repl("master.deinit(); del master; del Dut_master;", 0.2) 139 | self.double_serial.repl("slave.deinit(); del slave; del Double_slave;", 0.2) 140 | self.dut_serial.close_serial() 141 | self.double_serial.close_serial() 142 | 143 | if __name__ == '__main__': 144 | unittest.main() 145 | -------------------------------------------------------------------------------- /conftime_DS3231/test_conftime_DS3231.py: -------------------------------------------------------------------------------- 1 | # Do the serial interface between PC and DUT or DOUBLE 2 | from serial_interface_upython import SerialInterface 3 | # Library for testing with different asserts 4 | from should_dsl import should 5 | # Test class from wich our class inhereints 6 | import unittest 7 | # Operational System Interface 8 | import os 9 | import sys 10 | # Utils 11 | import time 12 | from time import sleep 13 | 14 | production_code = "dut_conf_time.py" 15 | double_code = "double_DS3231.py" 16 | auxiliar_code = "DS3231.py" 17 | build = "python -m mpy_cross -s -march=xtensa " 18 | DUT_PORT = "/dev/ttyUSB0" 19 | DOUBLE_PORT = "/dev/ttyUSB1" 20 | send = "ampy --delay 1 --port " 21 | # From set-up: 22 | # Building, connection and sending phase 23 | try: 24 | print("Building production code...") 25 | os.system(build+production_code) 26 | print("Building double code...") 27 | os.system(build+double_code) 28 | print("Building auxiliar code...") 29 | os.system(build+auxiliar_code) 30 | print("Cleaning the filesystem...") 31 | dut_serial = SerialInterface(DUT_PORT, 115200) 32 | dut_serial.connect_to_serial() 33 | dut_serial.clean_file_sys() 34 | dut_serial.close_serial() 35 | double_serial = SerialInterface(DOUBLE_PORT, 115200) 36 | double_serial.connect_to_serial() 37 | double_serial.clean_file_sys() 38 | double_serial.close_serial() 39 | print("Sending built production code...") 40 | os.system(send+DUT_PORT+" put "+production_code)#.replace(".py",".mpy")) 41 | print("Sending built auxiliar_code...") 42 | os.system(send+DUT_PORT+" put "+auxiliar_code)#.replace(".py",".mpy")) 43 | print("Sending built double code...") 44 | os.system(send+DOUBLE_PORT+" put "+double_code)#.replace(".py",".mpy")) 45 | except: 46 | sys.exit('fail to upload file(s)') 47 | # Uncomment the next line for not to run the Test 48 | # sys.exit() 49 | 50 | # Testing Phase 51 | class Test_DS3231(unittest.TestCase): 52 | #Creates a serial connection and import the classes 53 | def setUp(self): 54 | print('\n') 55 | print("Connecting to DUT device...") 56 | self.dut_serial = SerialInterface(DUT_PORT, 115200) 57 | self.dut_serial.connect_to_serial() 58 | print("Connecting to DOUBLE device...") 59 | self.double_serial = SerialInterface(DOUBLE_PORT, 115200) 60 | self.double_serial.connect_to_serial() 61 | self.dut_serial.repl("from dut_conf_time import ConfTime", 0.1) 62 | self.double_serial.repl("from double_DS3231 import DOUBLE_DS3231", 0.1) 63 | 64 | def test_set_date_time_static(self): 65 | print("\nTesting the method set_date_time() in the static mode") 66 | expected_datetime = [2019,10,23,4,10,51,32] # datatime format: [Year, month, day, weekday, hour, minute, second] 67 | print("Set value: "+str(expected_datetime)) 68 | # 1 - Objects Creation 69 | self.double_serial.repl("ds3231 = DOUBLE_DS3231(21,22)",0.2) 70 | self.dut_serial.repl("rtc_conf = ConfTime(21,22)",0.2) 71 | # 2 - Input Injection 72 | self.dut_serial.repl("rtc_conf.set_date_time("+str(expected_datetime)+")", 0.2) 73 | # 3 - Results gathering 74 | gotten_datetime = self.double_serial.repl("ds3231.DateTime()",0.2)[2] 75 | # 4 - Assertion 76 | gotten_datetime = gotten_datetime.decode() 77 | print("Gotten value: "+gotten_datetime) 78 | gotten_datetime |should| equal_to (str(expected_datetime)) 79 | 80 | 81 | # Using an internal rtc from the double device 82 | def test_set_date_time_dynamic(self): 83 | print("\nTesting the method set_date_time in the dynamic mode") 84 | expected_datetime = [2019,10,23,4,10,51,32] # datatime format: [Year, month, day, weekday, hour, minute, second] 85 | my_delay = 2 86 | print("Set value: "+str(expected_datetime)) 87 | print("Delay time: "+str(my_delay)) 88 | # 1 - Objects Creation 89 | self.double_serial.repl("ds3231 = DOUBLE_DS3231(21,22)",0.2) 90 | self.dut_serial.repl("rtc_conf = ConfTime(21,22)",0.2) 91 | # 2 - Input Injection 92 | self.dut_serial.repl("rtc_conf.set_date_time("+str(expected_datetime)+")", 0.4) 93 | self.double_serial.repl("ds3231.use_internal_rtc()", 0.2) 94 | sleep(my_delay) 95 | # This increment was done because of the sleep time - rtc continues counting time 96 | expected_datetime[6] = expected_datetime[6] + my_delay 97 | # 3 - Results gathering 98 | gotten_datetime = self.double_serial.repl("ds3231.DateTime()",0.2)[2] 99 | # 4 - Assertion 100 | gotten_datetime = gotten_datetime.decode() 101 | print("Gotten value: "+gotten_datetime) 102 | gotten_datetime |should| equal_to (str(expected_datetime)) 103 | 104 | def test_get_date_time(self): 105 | print("\nTesting the method get_date_time()") 106 | expected_datetime = [2019,10,23,4,10,51,32] # datatime format: [Year, month, day, weekday, hour, minute, second] 107 | print("Set value: "+str(expected_datetime)) 108 | # 1 - Objects Creation 109 | self.double_serial.repl("ds3231 = DOUBLE_DS3231(21,22)",0.2) 110 | self.dut_serial.repl("rtc_conf = ConfTime(21,22)",0.2) 111 | # 2 - Input Injection 112 | self.double_serial.repl("ds3231.DateTime("+str(expected_datetime)+")", 0.2) 113 | # 3 - Results gathering 114 | gotten_datetime = self.dut_serial.repl("rtc_conf.get_date_time()",0.2)[2] 115 | # 4 - Assertion 116 | gotten_datetime = gotten_datetime.decode() 117 | print("Gotten value: "+gotten_datetime) 118 | gotten_datetime |should| equal_to (str(expected_datetime)) 119 | 120 | # Test both set and get time, this case can be used along with a double device or the device itself (autotest) 121 | def test_set_get_date_time(self): 122 | print("\nTesting the methods set_date_time() and get_date_time()") 123 | expected_datetime = [2019,10,23,4,10,51,32] 124 | print("Set value: "+str(expected_datetime)) 125 | # 1 - Objects Creation 126 | self.double_serial.repl("ds3231 = DOUBLE_DS3231(21,22)",0.2) 127 | self.dut_serial.repl("rtc_conf = ConfTime(21,22)",0.2) 128 | # 2 - Input Injection 129 | self.dut_serial.repl("rtc_conf.set_date_time("+str(expected_datetime)+")", 0.2) 130 | # 3 - Results gathering 131 | gotten_datetime = self.dut_serial.repl("rtc_conf.get_date_time()",0.2)[2] 132 | # 4 - Assertion 133 | gotten_datetime = gotten_datetime.decode() 134 | print("Gotten value: "+gotten_datetime) 135 | gotten_datetime |should| equal_to (str(expected_datetime)) 136 | 137 | #closes serial and make the descomissioning 138 | def tearDown(self): 139 | # 5 - descomissioning 140 | self.dut_serial.repl("del rtc_conf; del ConfTime", 0.4) 141 | self.double_serial.repl("ds3231.deinit(); del ds3231; del DOUBLE_DS3231", 0.4) 142 | self.dut_serial.close_serial() 143 | self.double_serial.close_serial() 144 | 145 | if __name__ == '__main__': 146 | unittest.main() 147 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # micropython_test_lib 2 | 3 | This repository intends to present a method and the implementation for testing embedded micropython software using TDD (Test Driven Development) and HILS (Hardware in the loop Simulation). The tests are especially for drivers, that interact directly with external hardware. This repository contains multiple artifacts such as different test cases using different protocols (UART, I2C, GPIO, BLE, SPI) that serve as examples of how to test some drivers. It also contains utilities that made the tests possible and this guide for using all this tool. 4 | 5 | The purposed method is drawn in the figure below: 6 | 7 | ![Test Method](https://github.com/saramonteiro/micropython_test_lib/blob/master/images/method.png) 8 | 9 | The test architecture is compounded of 3 devices and 10 | 3 codes: 11 | * **Devices**: 12 | * **1 Computer**: hosts the test application and responsible for the test execution. 13 | * **2 microcontrollers (both are esp32)**: 14 | * **DUT (Device Under Test)**: hosts the production code that is the test’s target. 15 | * **DOUBLE**: another microcontroller that hosts the double code that plays the role of a (real) external peripheral, for example a RTC, a GPS, and even a simple led. The double provides inputs to the device under test and receives outputs from it, making the doubled devices transparent from the device under test’s viewpoint. 16 | * **Codes**: 17 | * **Test Code**: The test code is on the PC. It orchestrates the test, communicates to each device injecting commands and gathers results. Following the TDD philosophy, this software must be written before the production code. 18 | * **Double Code**: It's embedded on the DOUBLE. Its role is to pretend to be an external peripheral. During the development of this tool, some functional doubles were created. But It's expected that the community and the peripheral manufacturers produce their double code and make it available for test and development. 19 | * **Production Code**: It's the code we want to test! 20 | 21 | # Setting up the environment 22 | 23 | 1. **Micropython firmware** 24 | 25 | The first thing we have to do before running the tests is to erase the flash memory and to upload a micropython firmware. The latest micropython firmware may be downloaded from [micropython original firmwares](http://micropython.org/download#esp32). Download the latest generic idfv3 firmware. 26 | > The DUT will use this firmware in all the test cases. However, the DOUBLE will use this firmware only on the blink_led, GPS and BLE examples. On the RTC example, it will use this another third-party firmware: [micropython with i2c slave mode](https://github.com/loboris/MicroPython_ESP32_psRAM_LoBo/wiki/firmwares). On the SPI example, it will use the [micropython with spi slave mode](https://github.com/saramonteiro/micropython_test_lib/tree/master/SPI/pre-built-firmware). It has spi slave support and is part of this work. 27 | 28 | To upload the firmware we are going to use the `esptool`. It's a tool that allows us to erase the flash memory and write the firmware on it. Set aside a directory where you will download your firmwares and install esptool to do the upload. 29 | Inside this directory create a virtual environment: 30 | ``` 31 | python3 -m venv myfirmwares 32 | ``` 33 | Activate the virtual env with: 34 | ``` 35 | source myfirmwares/bin/activate 36 | ``` 37 | From inside it, install [esptool](https://pypi.org/project/esptool/) with: 38 | ``` 39 | pip install esptool 40 | ``` 41 | Erase the flash specifying the port with the following command: 42 | ``` 43 | esptool.py --port /dev/ttyUSB0 erase_flash 44 | ``` 45 | Finally do the firmware upload with: 46 | ``` 47 | esptool.py --chip esp32 --port /dev/ttyUSB0 --baud 460800 write_flash -z 0x1000 esp32-idf3-20200128-v1.12-96-gc3095b37e.bin 48 | ``` 49 | The last parameter is a binary. The firmware itself. 50 | 51 | Ready! You may now use picocom or another serial terminal tool to enter the repl. 52 | 53 | P.S: The I2C firmware has its own script that flashes the memory, but also uses esptool. When you download the firmware and unpack the zip, run the following command from the ep32 directory to upload the firmware: 54 | ``` 55 | ../flash.sh -p /dev/ttyUSB0 56 | ``` 57 | Always erase the flash before uploading. 58 | 59 | # Templates 60 | 61 | Now that you have the micropython firmware uploaded to the boards it's time to clone this project, install the dependencies and verify if everything is right. The templates have two goals: to serve as a starting point for developers to create their own tests and to verify if the dependencies were correctly installed. 62 | 63 | First, clone this project: 64 | ``` 65 | git clone https://github.com/saramonteiro/micropython_test_lib.git 66 | ``` 67 | Open the micropython_test_lib directory and create a virtual env inside it. 68 | ``` 69 | python3 -m venv test-env 70 | ``` 71 | Activate the virtual env with: 72 | ``` 73 | source test-env/bin/activate 74 | ``` 75 | Install all the required dependencies: 76 | ``` 77 | pip install -r requirements.txt 78 | ``` 79 | Connect the esp32 boards and check the USB port each device is connected to. Enter on Templates directory, open the `test_template.py` file and modify the constants `DUT_PORT` and `DOUBLE_PORT`according to your connection. Save it. Close it. And runt it: 80 | ``` 81 | python3 test_template.py -v 82 | ``` 83 | P.S: You may have to run this command with sudo since it requires permission to establish a serial connection. 84 | The test_template doesn't have any test case but it will test the environment and the communication to the boards. 85 | 86 | If everything is right, you should expect a screen like this: 87 | 88 | ![Installation ok](https://github.com/saramonteiro/micropython_test_lib/blob/master/images/ambiente_ok.png) 89 | 90 | # Running the Examples 91 | 92 | After checking your environment, try the examples only running the `test_*.py` files contained on the directories the same way you ran the `test_template.py`. Observe that there's a convention for the files' names. This makes it easy to identify the codes. 93 | More detailed information about each test and the electrical connection is kept inside each directory. 94 | 95 | P.S: It's recommended to reset the boards before running tests. 96 | 97 | # Troubleshooting 98 | 99 | * If you're having problems to upload the files or if it's not injecting commands properly, the DUT or the double may have entered on raw repl mode. To check it, you may use the picocom or other terminal emulation tools. To work around this problem, and others, it's recommended to reset the boards. This ensures there's no residual object. For problems like this, you should also check your cable and the configured USB port. 100 | * It's not recommended to interrupt tests since all tests have a routine of multiple steps from initialization to decommissioning. An interruption may lead to unexpected behavior. 101 | * This tool was designed to have all files pre-compiled before uploading, however, each firmware demands on a specific mpy-cross version. That's because many examples sent python files instead of micropython files. You may change the mpy-cross version in requirements.txt to pre-compile files for a specific firmware. 102 | * SPI and BLE examples are unstable. The [5489 issue](https://github.com/micropython/micropython/issues/5489) reports an inconsistent init time for BLE module, which is very recent. This may cause problems during the text executions because the test relies on a deterministic time. 103 | * To track the commands that are sent and the results that are gathered through serial you may uncomment the line ```print (response)``` on the module ```serial_interface_upython.py```. This will help for debugging purposes. 104 | 105 | # Future Works 106 | 107 | It's intended to become this tool into a command-line tool where dynamic parameters, such as USB port and others may be set on the terminal instead of being directly changed on code. 108 | -------------------------------------------------------------------------------- /BLE/ble_temperature_central.py: -------------------------------------------------------------------------------- 1 | # THIRD PARTY CODE -> Original from https://github.com/micropython/micropython/tree/master/examples/bluetooth 2 | # This example finds and connects to a BLE temperature sensor (e.g. the one in ble_temperature.py). 3 | 4 | import bluetooth 5 | import random 6 | import struct 7 | import time 8 | import micropython 9 | 10 | from ble_advertising import decode_services, decode_name 11 | 12 | from micropython import const 13 | _IRQ_CENTRAL_CONNECT = const(1 << 0) 14 | _IRQ_CENTRAL_DISCONNECT = const(1 << 1) 15 | _IRQ_GATTS_WRITE = const(1 << 2) 16 | _IRQ_GATTS_READ_REQUEST = const(1 << 3) 17 | _IRQ_SCAN_RESULT = const(1 << 4) 18 | _IRQ_SCAN_COMPLETE = const(1 << 5) 19 | _IRQ_PERIPHERAL_CONNECT = const(1 << 6) 20 | _IRQ_PERIPHERAL_DISCONNECT = const(1 << 7) 21 | _IRQ_GATTC_SERVICE_RESULT = const(1 << 8) 22 | _IRQ_GATTC_CHARACTERISTIC_RESULT = const(1 << 9) 23 | _IRQ_GATTC_DESCRIPTOR_RESULT = const(1 << 10) 24 | _IRQ_GATTC_READ_RESULT = const(1 << 11) 25 | _IRQ_GATTC_WRITE_STATUS = const(1 << 12) 26 | _IRQ_GATTC_NOTIFY = const(1 << 13) 27 | _IRQ_GATTC_INDICATE = const(1 << 14) 28 | _IRQ_ALL = const(0xffff) 29 | 30 | # org.bluetooth.service.environmental_sensing 31 | _ENV_SENSE_UUID = bluetooth.UUID(0x181A) 32 | # org.bluetooth.characteristic.temperature 33 | _TEMP_UUID = bluetooth.UUID(0x2A6E) 34 | _TEMP_CHAR = (_TEMP_UUID, bluetooth.FLAG_READ|bluetooth.FLAG_NOTIFY,) 35 | _ENV_SENSE_SERVICE = (_ENV_SENSE_UUID, (_TEMP_CHAR,),) 36 | 37 | # org.bluetooth.characteristic.gap.appearance.xml 38 | _ADV_APPEARANCE_GENERIC_THERMOMETER = const(768) 39 | 40 | class BLETemperatureCentral: 41 | def __init__(self, ble): 42 | self._ble = ble 43 | self._ble.active(True) 44 | self._ble.irq(handler=self._irq) 45 | 46 | self._reset() 47 | 48 | def _reset(self): 49 | # Cached name and address from a successful scan. 50 | self._name = None 51 | self._addr_type = None 52 | self._addr = None 53 | 54 | # Cached value (if we have one) 55 | self._value = None 56 | 57 | # Callbacks for completion of various operations. 58 | # These reset back to None after being invoked. 59 | self._scan_callback = None 60 | self._conn_callback = None 61 | self._read_callback = None 62 | 63 | # Persistent callback for when new data is notified from the device. 64 | self._notify_callback = None 65 | 66 | # Connected device. 67 | self._conn_handle = None 68 | self._value_handle = None 69 | 70 | def _irq(self, event, data): 71 | if event == _IRQ_SCAN_RESULT: 72 | addr_type, addr, connectable, rssi, adv_data = data 73 | if connectable and _ENV_SENSE_UUID in decode_services(adv_data): 74 | # Found a potential device, remember it and stop scanning. 75 | self._addr_type = addr_type 76 | self._addr = bytes(addr) # Note: The addr buffer is owned by modbluetooth, need to copy it. 77 | self._name = decode_name(adv_data) or '?' 78 | self._ble.gap_scan(None) 79 | 80 | elif event == _IRQ_SCAN_COMPLETE: 81 | if self._scan_callback: 82 | if self._addr: 83 | # Found a device during the scan (and the scan was explicitly stopped). 84 | self._scan_callback(self._addr_type, self._addr, self._name) 85 | self._scan_callback = None 86 | else: 87 | # Scan timed out. 88 | self._scan_callback(None, None, None) 89 | 90 | elif event == _IRQ_PERIPHERAL_CONNECT: 91 | # Connect successful. 92 | conn_handle, addr_type, addr, = data 93 | if addr_type == self._addr_type and addr == self._addr: 94 | self._conn_handle = conn_handle 95 | self._ble.gattc_discover_services(self._conn_handle) 96 | 97 | elif event == _IRQ_PERIPHERAL_DISCONNECT: 98 | # Disconnect (either initiated by us or the remote end). 99 | conn_handle, _, _, = data 100 | if conn_handle == self._conn_handle: 101 | # If it was initiated by us, it'll already be reset. 102 | self._reset() 103 | 104 | elif event == _IRQ_GATTC_SERVICE_RESULT: 105 | # Connected device returned a service. 106 | conn_handle, start_handle, end_handle, uuid = data 107 | if conn_handle == self._conn_handle and uuid == _ENV_SENSE_UUID: 108 | self._ble.gattc_discover_characteristics(self._conn_handle, start_handle, end_handle) 109 | 110 | elif event == _IRQ_GATTC_CHARACTERISTIC_RESULT: 111 | # Connected device returned a characteristic. 112 | conn_handle, def_handle, value_handle, properties, uuid = data 113 | if conn_handle == self._conn_handle and uuid == _TEMP_UUID: 114 | self._value_handle = value_handle 115 | # We've finished connecting and discovering device, fire the connect callback. 116 | if self._conn_callback: 117 | self._conn_callback() 118 | 119 | elif event == _IRQ_GATTC_READ_RESULT: 120 | # A read completed successfully. 121 | conn_handle, value_handle, char_data = data 122 | if conn_handle == self._conn_handle and value_handle == self._value_handle: 123 | self._update_value(char_data) 124 | if self._read_callback: 125 | self._read_callback(self._value) 126 | self._read_callback = None 127 | 128 | elif event == _IRQ_GATTC_NOTIFY: 129 | # The ble_temperature.py demo periodically notifies its value. 130 | conn_handle, value_handle, notify_data = data 131 | if conn_handle == self._conn_handle and value_handle == self._value_handle: 132 | self._update_value(notify_data) 133 | if self._notify_callback: 134 | self._notify_callback(self._value) 135 | 136 | 137 | # Returns true if we've successfully connected and discovered characteristics. 138 | def is_connected(self): 139 | return self._conn_handle is not None and self._value_handle is not None 140 | 141 | # Find a device advertising the environmental sensor service. 142 | def scan(self, callback=None): 143 | self._addr_type = None 144 | self._addr = None 145 | self._scan_callback = callback 146 | self._ble.gap_scan(2000, 30000, 30000) 147 | 148 | # Connect to the specified device (otherwise use cached address from a scan). 149 | def connect(self, addr_type=None, addr=None, callback=None): 150 | self._addr_type = addr_type or self._addr_type 151 | self._addr = addr or self._addr 152 | self._conn_callback = callback 153 | if self._addr_type is None or self._addr is None: 154 | return False 155 | self._ble.gap_connect(self._addr_type, self._addr) 156 | return True 157 | 158 | # Disconnect from current device. 159 | def disconnect(self): 160 | if not self._conn_handle: 161 | return 162 | self._ble.gap_disconnect(self._conn_handle) 163 | self._reset() 164 | 165 | # Issues an (asynchronous) read, will invoke callback with data. 166 | def read(self, callback): 167 | if not self.is_connected(): 168 | return 169 | self._read_callback = callback 170 | self._ble.gattc_read(self._conn_handle, self._value_handle) 171 | 172 | # Sets a callback to be invoked when the device notifies us. 173 | def on_notify(self, callback): 174 | self._notify_callback = callback 175 | 176 | def _update_value(self, data): 177 | # Data is sint16 in degrees Celsius with a resolution of 0.01 degrees Celsius. 178 | self._value = struct.unpack('`_ 37 | * Adafruit `Ultimate GPS FeatherWing `_ 38 | 39 | **Software and Dependencies:** 40 | 41 | * MicroPython: 42 | https://github.com/micropython/micropython 43 | 44 | """ 45 | __version__ = "0.0.0-auto.0" 46 | __repo__ = "https://github.com/alexmrqt/Adafruit_CircuitPython_GPS.git" 47 | 48 | # Internal helper parsing functions. 49 | # These handle input that might be none or null and return none instead of 50 | # throwing errors. 51 | def _parse_degrees(nmea_data): 52 | # Parse a NMEA lat/long data pair 'dddmm.mmmm' into a pure degrees value. 53 | # Where ddd is the degrees, mm.mmmm is the minutes. 54 | if nmea_data is None or len(nmea_data) < 3: 55 | return None 56 | raw = float(nmea_data.decode()) 57 | deg = raw // 100 58 | minutes = raw % 100 59 | return deg + minutes/60 60 | 61 | def _parse_int(nmea_data): 62 | if nmea_data is None or nmea_data == b'': 63 | return None 64 | return int(nmea_data) 65 | 66 | def _parse_float(nmea_data): 67 | if nmea_data is None or nmea_data == b'': 68 | return None 69 | return float(nmea_data.decode()) 70 | 71 | # lint warning about too many attributes disabled 72 | #pylint: disable-msg=R0902 73 | class GPS: 74 | """GPS parsing module. Can parse simple NMEA data sentences from serial GPS 75 | modules to read latitude, longitude, and more. 76 | 77 | :param uart: The `UART` object to use. 78 | """ 79 | def __init__(self, uart): 80 | self._uart = uart 81 | # Initialize null starting values for GPS attributes. 82 | self.timestamp_utc = None 83 | self.latitude = None 84 | self.longitude = None 85 | self.fix_quality = None 86 | self.satellites = None 87 | self.horizontal_dilution = None 88 | self.altitude_m = None 89 | self.height_geoid = None 90 | self.velocity_knots = None 91 | self.speed_knots = None 92 | self.track_angle_deg = None 93 | 94 | def update(self): 95 | """Check for updated data from the GPS module and process it 96 | accordingly. Returns True if new data was processed, and False if 97 | nothing new was received. 98 | """ 99 | # Grab a sentence and check its data type to call the appropriate 100 | # parsing function. 101 | sentence = self._parse_sentence() 102 | if sentence is None: 103 | return False 104 | data_type, args = sentence 105 | data_type = data_type.upper() 106 | if data_type == b'GPGGA': # GGA, 3d location fix 107 | self._parse_gpgga(args) 108 | elif data_type == b'GPRMC': # RMC, minimum location info 109 | self._parse_gprmc(args) 110 | return True 111 | 112 | def send_command(self, command, add_checksum=True): 113 | """Send a command string to the GPS. If add_checksum is True (the 114 | default) a NMEA checksum will automatically be computed and added. 115 | Note you should NOT add the leading $ and trailing * to the command 116 | as they will automatically be added! 117 | """ 118 | self._uart.write('$') 119 | self._uart.write(command) 120 | if add_checksum: 121 | checksum = 0 122 | for char in command: 123 | checksum ^= ord(char) 124 | self._uart.write('*') 125 | self._uart.write('{:02x}'.format(checksum).upper()) 126 | self._uart.write('\r\n') 127 | 128 | @property 129 | def has_fix(self): 130 | """True if a current fix for location information is available.""" 131 | return self.fix_quality is not None and self.fix_quality >= 1 132 | 133 | def _parse_sentence(self): 134 | # Parse any NMEA sentence that is available. 135 | sentence = self._uart.readline() 136 | if sentence is None or sentence == b'' or len(sentence) < 1: 137 | return None 138 | sentence = sentence.strip() 139 | # Look for a checksum and validate it if present. 140 | if len(sentence) > 7 and sentence[-3] == ord('*'): 141 | # Get included checksum, then calculate it and compare. 142 | expected = int(sentence[-2:], 16) 143 | actual = 0 144 | for i in range(1, len(sentence)-3): 145 | actual ^= sentence[i] 146 | if actual != expected: 147 | return None # Failed to validate checksum. 148 | # Remove checksum once validated. 149 | sentence = sentence[:-3] 150 | # Parse out the type of sentence (first string after $ up to comma) 151 | # and then grab the rest as data within the sentence. 152 | delineator = sentence.find(b',') 153 | if delineator == -1: 154 | return None # Invalid sentence, no comma after data type. 155 | data_type = sentence[1:delineator] 156 | return (data_type, sentence[delineator+1:]) 157 | 158 | def _parse_gpgga(self, args): 159 | # Parse the arguments (everything after data type) for NMEA GPGGA 160 | # 3D location fix sentence. 161 | data = args.split(b',') 162 | if data is None or len(data) != 14: 163 | return # Unexpected number of params. 164 | # Parse fix time. 165 | time_utc = int(_parse_float(data[0])) 166 | if time_utc is not None: 167 | hours = time_utc // 10000 168 | mins = (time_utc // 100) % 100 169 | secs = time_utc % 100 170 | # Set or update time to a friendly python time struct. 171 | if self.timestamp_utc is not None: 172 | self.timestamp_utc = ( 173 | self.timestamp_utc[0], self.timestamp_utc[1], 174 | self.timestamp_utc[2], hours, mins, secs, 0, 0) 175 | else: 176 | self.timestamp_utc = (0, 0, 0, hours, mins, secs, 0, 0) 177 | # Parse latitude and longitude. 178 | self.latitude = _parse_degrees(data[1]) 179 | if self.latitude is not None and \ 180 | data[2] is not None and data[2].lower() == b's': 181 | self.latitude *= -1.0 182 | self.longitude = _parse_degrees(data[3]) 183 | if self.longitude is not None and \ 184 | data[4] is not None and data[4].lower() == b'w': 185 | self.longitude *= -1.0 186 | # Parse out fix quality and other simple numeric values. 187 | self.fix_quality = _parse_int(data[5]) 188 | self.satellites = _parse_int(data[6]) 189 | self.horizontal_dilution = _parse_float(data[7]) 190 | self.altitude_m = _parse_float(data[8]) 191 | self.height_geoid = _parse_float(data[10]) 192 | 193 | def _parse_gprmc(self, args): 194 | # Parse the arguments (everything after data type) for NMEA GPRMC 195 | # minimum location fix sentence. 196 | data = args.split(b',') 197 | if data is None or len(data) < 11 or data[0] is None: 198 | return # Unexpected number of params. 199 | # Parse fix time. 200 | time_utc = int(_parse_float(data[0])) 201 | if time_utc is not None: 202 | hours = time_utc // 10000 203 | mins = (time_utc // 100) % 100 204 | secs = time_utc % 100 205 | # Set or update time to a friendly python time struct. 206 | if self.timestamp_utc is not None: 207 | self.timestamp_utc = ( 208 | self.timestamp_utc[0], self.timestamp_utc[1], 209 | self.timestamp_utc[2], hours, mins, secs, 0, 0) 210 | else: 211 | self.timestamp_utc = (0, 0, 0, hours, mins, secs, 0, 0) 212 | # Parse status (active/fixed or void). 213 | status = data[1] 214 | self.fix_quality = 0 215 | if status is not None and status.lower() == b'a': 216 | self.fix_quality = 1 217 | # Parse latitude and longitude. 218 | self.latitude = _parse_degrees(data[2]) 219 | if self.latitude is not None and \ 220 | data[3] is not None and data[3].lower() == b's': 221 | self.latitude *= -1.0 222 | self.longitude = _parse_degrees(data[4]) 223 | if self.longitude is not None and \ 224 | data[5] is not None and data[5].lower() == b'w': 225 | self.longitude *= -1.0 226 | # Parse out speed and other simple numeric values. 227 | self.speed_knots = _parse_float(data[6]) 228 | self.track_angle_deg = _parse_float(data[7]) 229 | # Parse date. 230 | if data[8] is not None and len(data[8]) == 6: 231 | day = int(data[8][0:2]) 232 | month = int(data[8][2:4]) 233 | year = 2000 + int(data[8][4:6]) # Y2k bug, 2 digit date assumption. 234 | # This is a problem with the NMEA 235 | # spec and not this code. 236 | if self.timestamp_utc is not None: 237 | # Replace the timestamp with an updated one. 238 | self.timestamp_utc = (year, month, day, 239 | self.timestamp_utc[3], 240 | self.timestamp_utc[4], 241 | self.timestamp_utc[5], 242 | 0, 243 | 0) 244 | else: 245 | # Time hasn't been set so create it. 246 | self.timestamp_utc = (year, month, day, 0, 0, 0, 0, 0) 247 | --------------------------------------------------------------------------------