martynwheeler / u-lora

raspi-lora for micropython
GNU General Public License v3.0
71 stars 10 forks source link

Continue refactor and testing of the code #15

Open rkompass opened 11 months ago

rkompass commented 11 months ago

@davefes: I continue here from our micropython discussion:

I got the module connected. No SPI problems. Had to correct my code again (still little flaws:)

lora_rfm95.py:

from ucollections import namedtuple
from urandom import getrandbits
from umachine import Pin
from utime import time, sleep_ms

# -----  Constants -----
MODE_SLEEP  = const(0x00)
MODE_STDBY  = const(0x01)
MODE_TX     = const(0x03)
MODE_RXCONT = const(0x05)
MODE_CAD    = const(0x07)
LONG_RANGE_MODE = const(0x80)

class LoRa(object):

    Bw125Cr45Sf128 = (0x72, 0x74, 0x04)   # Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on. Default medium range
    Bw500Cr45Sf128 = (0x92, 0x74, 0x04)   # Bw = 500 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on. Fast+short range
    Bw31_25Cr48Sf512 = (0x48, 0x94, 0x04) # Bw = 31.25 kHz, Cr = 4/8, Sf = 512chips/symbol, CRC on. Slow+long range
    Bw125Cr48Sf4096 = (0x78, 0xc4, 0x0c)  # Bw = 125 kHz, Cr = 4/8, Sf = 4096chips/symbol, low data rate, CRC on. Slow+long range
    Bw125Cr45Sf2048 = (0x72, 0xb4, 0x04)  # Bw = 125 kHz, Cr = 4/5, Sf = 2048chips/symbol, CRC on. Slow+long range

    def __init__(self, spi, cs, pirq, addr, res=None, freq=868.0, tx_power=14,
                 modem_config=Bw125Cr45Sf128, rcv_all=False, acks=False, crypto=None):
        """
        LoRa(spi, cs, itr, res=None, addr, freq=868.0, tx_power=14,
                 modem_conf=Bw125Cr45Sf128, receive_all=False, acks=False, crypto=None)
        spi: spi object
        cs: chip select (NSS) pin (mode = Pin.OUT, value=1)
        pirq: interrupt pin (mode = Pin.IN)
        res: reset pin (optional, mode = Pin.OUT, value=1)
        addr: address of this device [0-254]
        freq: frequency in MHz (default: 868.0)
        tx_power: transmit power in dBm (default: 14)
        modem_config: modem configuration, (default: LoRa.Bw125Cr45Sf128 is compatible with the Radiohead library)
        rcv_all: if True, don't filter packets on address
        acks: if True, request acknowledgments
        crypto: if desired, an instance of ucrypto AES (https://docs.pycom.io/firmwareapi/micropython/ucrypto/) - not tested
        """

        self.spi = spi              # spi object
        cs(1); self.cs = cs         # chip select (NSS) pin
        self.pirq = pirq            # interrupt pin
        self.res = res              # optional reset pin

        self.addr = addr            # other arguments
        self.freq = freq
        self.tx_power = max(min(tx_power, 23), 5)
        self.modem_config = modem_config
        self.rcv_all = rcv_all
        self.acks = acks
        self.crypto = crypto

        self.mode = None
        self._last_header_id = 0
        self._last_payload = None
        self._cad = None
        self.cad_timeout = 0
        self.send_retries = 2
        self.wait_packet_sent_timeout = 0.2
        self.retry_timeout = 0.2

        pirq.irq(trigger=Pin.IRQ_RISING, handler=self._handle_interrupt)   # setup interrupt

        self.reset()                                                       # reset the board
        self.set_mode(MODE_SLEEP | LONG_RANGE_MODE)                        # set mode
        sleep_ms(100)         # v-- REG_01_OP_MODE,  check if mode is set, also tests SPI communication
        assert self._spi_read(0x01) == (MODE_SLEEP | LONG_RANGE_MODE), "LoRa initialization failed" 

        self._spi_write(0x0e, 0)                                           # REG_0E_FIFO_TX_BASE_ADDR
        self._spi_write(0x0f, 0)                                           # REG_0F_FIFO_RX_BASE_ADDR

        self.set_mode(MODE_STDBY)
        self.set_modem_config(self.modem_config)                           # set modem config

        # set preamble length (8)
        self._spi_write(0x20, 0)                                           # REG_20_PREAMBLE_MSB
        self._spi_write(0x21, 8)                                           # REG_21_PREAMBLE_LSB

        # set frequency
        self.set_frequency(freq)

        # Set tx power
        if self.tx_power > 20:
            self._spi_write(0x4d, 0x07)                                    # REG_4D_PA_DAC,  0x07 = PA_DAC_ENABLE
            self.tx_power -= 3
        else:
            self._spi_write(0x4d, 0x04)                                    # REG_4D_PA_DAC,  PA_DAC_DISABLE = 0x04
        self._spi_write(0x09, 0x80 | (self.tx_power - 5))                  # REG_09_PA_CONFIG,  PA_SELECT = 0x80

    def on_recv(self, message):
        pass   # This should be overridden by the user

    def reset(self):
        if isinstance(self.res, Pin):
            self.res(0)
            sleep_ms(1)   # 100 us at least
            self.res(1)
            sleep_ms(5)   # 5 ms at least

    def set_mode(self, mode): # mode .. MODE_SLEEP, MODE_STDBY, MODE_TX, MODE_RXCONT or MODE_CAD
        if self.mode != mode:
            self._spi_write(0x01, mode)                                    # REG_01_OP_MODE
            if mode in (MODE_TX, MODE_RXCONT, MODE_CAD):
                self._spi_write(0x40, {MODE_TX:0x40, MODE_RXCONT:0x00, MODE_CAD:0x80}[mode])  # REG_40_DIO_MAPPING1
            self.mode = mode            #  ^--- Interrupt on TxDone, RxDone or CadDone

    def set_modem_config(self, config):
        self._spi_write(0x1d, config[0])                                   # REG_1D_MODEM_CONFIG1
        self._spi_write(0x1e, config[1])                                   # REG_1E_MzDEM_CONFIG2
        self._spi_write(0x26, config[2])                                   # REG_26_MODEM_CONFIG3

    def set_frequency(self, freq):
        frf = int((self.freq * 1000000.0) / 61.03516)    # 61.03516 = (FXOSC / 524288); FXOSC = 32000000.0
        self._spi_write(0x06, (frf >> 16) & 0xff)                          # REG_06_FRF_MSB
        self._spi_write(0x07, (frf >> 8) & 0xff)                           # REG_07_FRF_MID
        self._spi_write(0x08, frf & 0xff)                                  # REG_08_FRF_LSB

    def _is_channel_active(self):
        self.set_mode(MODE_CAD)

        while self.mode == MODE_CAD:
            yield

        return self._cad

    def wait_cad(self):
        if not self.cad_timeout:
            return True

        start = time()
        for status in self._is_channel_active():
            if time() - start < self.cad_timeout:
                return False

            if status is None:
                sleep_ms(100)
                continue
            else:
                return status

    def wait_packet_sent(self):
        # wait for `_handle_interrupt` to switch the mode back
        start = time()
        while time() - start < self.wait_packet_sent_timeout:
            if self.mode != MODE_TX:
                return True

        return False

    def send(self, data, header_to, header_id=0, header_flags=0):
        self.wait_packet_sent()
        self.set_mode(MODE_STDBY)
        self.wait_cad()

        header = [header_to, self.addr, header_id, header_flags]
        if type(data) == int:
            data = [data]
        elif type(data) == bytes:
            data = [p for p in data]
        elif type(data) == str:
            data = [ord(s) for s in data]

        if self.crypto:
            data = [b for b in self._encrypt(bytes(data))]

        payload = header + data
        self._spi_write(0x0d, 0)                            # REG_0D_FIFO_ADDR_PTR
        self._spi_write(0x00, payload)                      # REG_00_FIFO
        self._spi_write(0x22, len(payload))                 # REG_22_PAYLOAD_LENGTH
        self.set_mode(MODE_TX)

        return True

    def send_to_wait(self, data, header_to, header_flags=0, retries=3):
        self._last_header_id = (self._last_header_id + 1) % 256

        for _ in range(retries + 1):
            if self._acks:
                header_flags |= 0x40                        # 0x40 = FLAGS_REQ_ACK
            self.send(data, header_to, header_id=self._last_header_id, header_flags=header_flags)
            self.set_mode(MODE_RXCONT)

            if (not self._acks) or header_to == 255:  # Don't wait for acks from a broadcast message,  255 = BROADCAST_ADDRESS
                return True

            start = time()
            while time() - start < self.retry_timeout + (self.retry_timeout * (getrandbits(16) / (2**16 - 1))):
                if self._last_payload:
                    if self._last_payload.header_to == self.addr and \
                            self._last_payload.header_flags & 0x80 and \
                            self._last_payload.header_id == self._last_header_id:   # 0x80 = FLAGS_ACK
                        return True   # We got an ACK
        return False

    def send_ack(self, header_to, header_id):
        self.send(b'!', header_to, header_id, 0x80)                     # 0x80 = FLAGS_ACK
        self.wait_packet_sent()

    def _spi_write(self, register, payload):
        if type(payload) == int:
            payload = [payload]
        elif type(payload) == bytes:
            payload = [p for p in payload]
        elif type(payload) == str:
            payload = [ord(s) for s in payload]
        self.cs.value(0)
        self.spi.write(bytes([register | 0x80] + payload))
        self.cs.value(1)

    def _spi_read(self, register, length=1):
        self.cs.value(0)
        if length == 1:
            data = self.spi.read(length + 1, register)[1]
        else:
            data = self.spi.read(length + 1, register)[1:]
        self.cs.value(1)
        return data

#     def _spi_read(self, register, length=1):
#         self.cs(0)
#         data = self.spi.read(length + 1, register)[1:]
#         self.cs(1)
#         return data

    def _decrypt(self, message):
        decr_msg = self.crypto.decrypt(message)
        l = decr_msg[0]
        return decr_msg[1:l+1]

    def _encrypt(self, message):
        l = len(message)
        padding = bytes(15-l%16)  # same as bytes(((math.ceil((l + 1) / 16) * 16) - (l + 1)) * [0])
        return self.crypto.encrypt(bytes([l]) + message + padding)

    def _handle_interrupt(self, channel):
        irq_flags = self._spi_read(0x12)                          # REG_12_IRQ_FLAGS

        if self.mode == MODE_RXCONT and (irq_flags & 0x40):       # 0x40 = RX_DONE
            packet_len = self._spi_read(0x13)                     # REG_13_RX_NB_BYTES
            self._spi_write(0x0d, self._spi_read(0x10))           # REG_0D_FIFO_ADDR_PTR, REG_10_FIFO_RX_CURRENT_ADDR

            packet = self._spi_read(0x00, packet_len)             # REG_00_FIFO
            self._spi_write(0x12, 0xff)                           # REG_12_IRQ_FLAGS, Clear all IRQ flags

            snr = self._spi_read(0x19) / 4                        # REG_19_PKT_SNR_VALUE
            rssi = self._spi_read(0x1a)                           # REG_1A_PKT_RSSI_VALUE

            if snr < 0:
                rssi = snr + rssi
            else:
                rssi = rssi * 16 / 15

            if self._freq >= 779:
                rssi = round(rssi - 157, 2)
            else:
                rssi = round(rssi - 164, 2)

            if packet_len >= 4:
                header_to = packet[0]
                header_from = packet[1]
                header_id = packet[2]
                header_flags = packet[3]
                message = bytes(packet[4:]) if packet_len > 4 else b''

                if (self.addr != header_to) and (header_to != 255) and (self._receive_all is False):  # 255 = BROADCAST_ADDRESS
                    return

                if self.crypto and len(message) % 16 == 0:
                    message = self._decrypt(message)

                if self._acks and header_to == self.addr and header_flags & 0x40 and not header_flags & 0x80:
                    self.send_ack(header_from, header_id)             # ^-- 0x40 = FLAGS_REQ_ACK,       0x80 = FLAGS_ACK

                self.set_mode(MODE_RXCONT)

                self._last_payload = namedtuple("Payload",
                    ['message', 'header_to', 'header_from', 'header_id', 'header_flags', 'rssi', 'snr']
                )(message, header_to, header_from, header_id, header_flags, rssi, snr)

                if not header_flags & 0x80:     # FLAGS_ACK = 0x80
                    self.on_recv(self._last_payload)

        elif self.mode == MODE_TX and (irq_flags & 0x08):   # 0x08 = TX_DONE
            self.set_mode(MODE_STDBY)

        elif self.mode == MODE_CAD and (irq_flags & 0x04):  # 0x04 = CAD_DONE 
            self._cad = irq_flags & 0x01            # 0x01 = CAD_DETECTED
            self.set_mode(MODE_STDBY)

        self._spi_write(0x12, 0xff)   # REG_12_IRQ_FLAGS,  Clear all IRQ flags

and

from utime import sleep
from lora_rfm95 import LoRa
from umachine import Pin

# Lora Parameters
LORA_POW = 12
CLIENT_ADDRESS = 1
SERVER_ADDRESS = 2

# WeAct Blackpill STM32F411: We use SPI2 with (NSS, SCK, MISO, MOSI) = (Y5, Y6, Y7, Y8) = (PB12, PB13, PB14, PB15)
from pyb import SPI
spi = SPI(2, SPI.MASTER, baudrate=500_000, polarity=0, phase=0) # SCK=PB13, MISO=PB14, MOSI=PB15

# WeAct Blackpill STM32F411: We use SoftSPI
# from umachine import SoftSPI
# spi = SoftSPI(baudrate=100_000, polarity=0, phase=0, sck=Pin('PB13'), mosi=Pin('PB15'), miso=Pin('PB14'))

cs=Pin('PB12', Pin.OUT, value=1)
pirq=Pin('PA8', Pin.IN)
res=Pin('PA9', Pin.OUT, value=1)

led=Pin('PC13', Pin.OUT, value=0)

lora = LoRa(spi, cs=cs, pirq=pirq, res=res, addr=CLIENT_ADDRESS, modem_config=LoRa.Bw125Cr45Sf128, tx_power=LORA_POW)

# loop and send data
#while True:
#    lora.send_to_wait('Test msg', SERVER_ADDRESS)
lora.send('Test msg', SERVER_ADDRESS)
print ('sent')
sleep(1)
led(1)    # led off
sleep(0.5)

As it seems I have to solder another module (got 5) for receiving.

davefes commented 10 months ago

Just an observation ... Bw125Cr45Sf2048 seems to work well, but with Bw125Cr48Sf4096 the message comes through 4 times.

The timeouts (wait_packet_sent_timeout_ms, retry_timeout_ms and maybe cad_timeout_ms) seem to need tweaking depending on MODEM_CONFIG. Maybe message length is another variable.

I see in the micropython-lib lora that there is some timeout adjustment around line 729

davefes commented 10 months ago

@rkompass The main issue I am facing is that my sensor links using Wei's code may send a corrupted message, but at least an hour later it tries again ... so the odd missed data is not a problem. On a LoRa control link "missed messages" are a problem.

In ulora.py , the send_wait() method tries 4 times and the real plus is that you get an ACK sent back to the sender.

Have you made any further progress?

rkompass commented 10 months ago

I just tried the micropython-lib SX1276 version of reliable sending and receiving. Got sender and receiver to run, but there was no communication. I will have to repeat this with the SX1276 boards that I got yesterday (another run of soldering).

@davefes I saw that you posted the same observation on MP discussions. Cannot solve it at the moment, but will solve it later.

davefes commented 10 months ago

Appears that any "PA switching " that takes place is turning the whole TX on/off, as well as any possible antenna port selection.