diff --git a/examples/40-fm-tuner-rda5807/_steam_klub_test.py b/examples/40-fm-tuner-rda5807/_steam_klub_test.py index 0268676..6009059 100644 --- a/examples/40-fm-tuner-rda5807/_steam_klub_test.py +++ b/examples/40-fm-tuner-rda5807/_steam_klub_test.py @@ -15,62 +15,67 @@ import time from machine import Pin, SoftI2C, RTC, PWM from math import floor -from dht import DHT11 +# from dht import DHT11 # External modules import ssd1306 # OLED -from bh1750 import BH1750 # Lux meter +# from bh1750 import BH1750 # Lux meter from bmp180 import BMP180 # Pressure meter -from MPU6050 import MPU6050 # Accelerometer + gyroscope +# from MPU6050 import MPU6050 # Accelerometer + gyroscope import rda5807 # FM radio module # DHT11: Data - 4 # Temperature + Humidity -d = DHT11(Pin(4, Pin.IN, Pin.PULL_UP)) # The input mode and pull-up need to be set manually! +# d = DHT11(Pin(4, Pin.IN, Pin.PULL_UP)) # The input mode and pull-up need to be set manually! # Piezo buzzer - 13 -buzzer = PWM(Pin(13, Pin.OUT), duty=0) # duty=0 prevents default waveform from starting immediately +# buzzer = PWM(Pin(13, Pin.OUT), duty=0) # duty=0 prevents default waveform from starting immediately # PIR sensor: GPIO 14 -pir = Pin(14, Pin.IN) +pir = Pin(15, Pin.IN) # Capacitive touch sensor: GPIO 12 -touch = Pin(12, Pin.IN) +# touch = Pin(12, Pin.IN) # I2C devices: SDA - 21, SCK - 22 -i2c = SoftI2C(sda=Pin(21), scl=Pin(22)) +i2c = SoftI2C(sda=Pin(21), scl=Pin(22), freq=400_000) - -# OLED +# OLED display = ssd1306.SSD1306_I2C(128, 32, i2c) # using default address 0x3C # Lux meter -bh1750 = BH1750(0x23, i2c) +# bh1750 = BH1750(0x23, i2c) # Pressure meter bmp180 = BMP180(i2c) bmp180.oversample_sett = 2 bmp180.baseline = 101325 +# Led & buttons +led = Pin(2, Pin.OUT) +led.off() +btn_gr = Pin(19, Pin.IN, Pin.PULL_UP) +btn_rd = Pin(18, Pin.IN, Pin.PULL_UP) +btn_rot = Pin(25, Pin.IN, Pin.PULL_UP) + # Accelero + gyroscope -mpu = MPU6050(i2c) +# mpu = MPU6050(i2c) # FM Radio module radio = rda5807.Radio(i2c) -time.sleep(0.1) # Let the radio initialize!!! Without the sleep the module does not work! +time.sleep_ms(100) # Let the radio initialize!!! Without the sleep the module does not work! # init with default settings radio.set_volume(1) # 0-15 radio.set_frequency_MHz(103.0) # Radio Krokodyl (Brno) radio.mute(False) # Piezo buzzer 100ms beep -buzzer.freq(4095) -buzzer.duty(50) -time.sleep(0.1) -buzzer.duty(0) -buzzer.deinit() - +# buzzer.freq(4095) +# buzzer.duty(50) +# time.sleep(0.1) +# buzzer.duty(0) +# buzzer.deinit() # Custom function definitions @@ -78,46 +83,58 @@ def floatToStr(f: float): return str(round(f, 2)) # Max 2 decimal digits - -# Main loop -while True: - display.fill(0) - - # Lux + pressure meter + PIR + Capacitive touch - display.text(floatToStr(bh1750.measurement)+' lx', 0, 0, 1) - display.text(floatToStr(bmp180.pressure/1000)+' kPa', 0, 8, 1) - display.text(floatToStr(bmp180.temperature)+' \'C', 0, 16, 1) - display.text('PIR: '+str(pir.value()), 0, 24, 1) - display.text('Touch: '+str(touch.value()), 56, 24, 1) - - # Accelerometer - #accel = mpu.read_accel_data() - #gyro = mpu.read_gyro_data() - #temp = mpu.read_temperature() - #Xstr = 'X % 3d.%02d % 3d.%02d' % (floor(accel["x"]), round(100*(accel["x"]%1)), floor(gyro["x"]), round(100*(gyro["x"]%1))) - #Ystr = 'Y % 3d.%02d % 3d.%02d' % (floor(accel["y"]), round(100*(accel["y"]%1)), floor(gyro["y"]), round(100*(gyro["y"]%1))) - #Zstr = 'Z % 3d.%02d % 3d.%02d' % (floor(accel["z"]), round(100*(accel["z"]%1)), floor(gyro["z"]), round(100*(gyro["z"]%1))) - #display.text(Xstr, 0, 0, 1) - #display.text(Ystr, 0, 8, 1) - #display.text(Zstr, 0, 16, 1) - #display.text('Temp '+floatToStr(temp)+' \'C', 0, 24, 1) - - # DHT11: Temperature + Humidity - #try: - # d.measure() - # display.text('DHT11', 0, 0, 1) - # display.text('Temp: '+str(d.temperature())+' \'C', 0, 10, 1) - # display.text('Humi: '+str(d.humidity())+' %', 0, 20, 1) - #except: - # display.text('DHT11 meas. fail', 0, 0, 1) - - # FM Radio - #display.text(str(radio.get_frequency_MHz())+' MHz', 0, 0, 1) - #radio.update_rds() - #print(radio.get_rds_block_group()) # How to decode RDS? - #time.sleep(0.5) - - - display.show() - time.sleep(0.01) - +try: + # Main loop + while True: + if (btn_gr.value() == 0) or (btn_rd.value() == 0) or (btn_rot.value() == 0): + led.on() + else: + led.off() + + display.fill(0) + + # Lux + pressure meter + PIR + Capacitive touch + # display.text(floatToStr(bh1750.measurement)+' lx', 0, 0, 1) + # display.text(floatToStr(bmp180.pressure/1000)+' kPa', 0, 8, 1) + # display.text(floatToStr(bmp180.temperature)+' \'C', 0, 16, 1) + display.text('PIR: '+str(pir.value()), 0, 24, 1) + # display.text('Touch: '+str(touch.value()), 56, 24, 1) + + # Accelerometer + #accel = mpu.read_accel_data() + #gyro = mpu.read_gyro_data() + #temp = mpu.read_temperature() + #Xstr = 'X % 3d.%02d % 3d.%02d' % (floor(accel["x"]), round(100*(accel["x"]%1)), floor(gyro["x"]), round(100*(gyro["x"]%1))) + #Ystr = 'Y % 3d.%02d % 3d.%02d' % (floor(accel["y"]), round(100*(accel["y"]%1)), floor(gyro["y"]), round(100*(gyro["y"]%1))) + #Zstr = 'Z % 3d.%02d % 3d.%02d' % (floor(accel["z"]), round(100*(accel["z"]%1)), floor(gyro["z"]), round(100*(gyro["z"]%1))) + #display.text(Xstr, 0, 0, 1) + #display.text(Ystr, 0, 8, 1) + #display.text(Zstr, 0, 16, 1) + #display.text('Temp '+floatToStr(temp)+' \'C', 0, 24, 1) + + # DHT11: Temperature + Humidity + #try: + # d.measure() + # display.text('DHT11', 0, 0, 1) + # display.text('Temp: '+str(d.temperature())+' \'C', 0, 10, 1) + # display.text('Humi: '+str(d.humidity())+' %', 0, 20, 1) + #except: + # display.text('DHT11 meas. fail', 0, 0, 1) + + # FM Radio + display.text(str(radio.get_frequency_MHz())+' MHz', 0, 0, 1) + rssi = radio.get_signal_strength() + print(rssi, "dBm") + radio.update_rds() + # print(radio.get_rds_block_group()) # How to decode RDS? + print(radio.station_name) + + display.show() + time.sleep_ms(100) + +except KeyboardInterrupt: + # This part runs when Ctrl+C is pressed + print("\nProgram stopped. Exiting...") + + # Optional cleanup code + led.off() diff --git a/examples/40-fm-tuner-rda5807/bmp180.py b/examples/40-fm-tuner-rda5807/bmp180.py new file mode 100644 index 0000000..46429ff --- /dev/null +++ b/examples/40-fm-tuner-rda5807/bmp180.py @@ -0,0 +1,189 @@ +# https://github.com/micropython-IMU/micropython-bmp180/blob/master/bmp180.py + +''' +bmp180 is a micropython module for the Bosch BMP180 sensor. It measures +temperature as well as pressure, with a high enough resolution to calculate +altitude. +Breakoutboard: http://www.adafruit.com/products/1603 +data-sheet: http://ae-bst.resource.bosch.com/media/products/dokumente/ +bmp180/BST-BMP180-DS000-09.pdf + +The MIT License (MIT) +Copyright (c) 2014 Sebastian Plamauer, oeplse@gmail.com +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +''' + +from ustruct import unpack as unp +from machine import I2C, Pin +import math +import time + +# BMP180 class +class BMP180(): + ''' + Module for the BMP180 pressure sensor. + ''' + + _bmp_addr = 119 # adress of BMP180 is hardcoded on the sensor + + # init + def __init__(self, i2c_bus): + + # create i2c obect + _bmp_addr = self._bmp_addr + self._bmp_i2c = i2c_bus + self._bmp_i2c.start() + self.chip_id = self._bmp_i2c.readfrom_mem(_bmp_addr, 0xD0, 2) + # read calibration data from EEPROM + self._AC1 = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xAA, 2))[0] + self._AC2 = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xAC, 2))[0] + self._AC3 = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xAE, 2))[0] + self._AC4 = unp('>H', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xB0, 2))[0] + self._AC5 = unp('>H', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xB2, 2))[0] + self._AC6 = unp('>H', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xB4, 2))[0] + self._B1 = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xB6, 2))[0] + self._B2 = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xB8, 2))[0] + self._MB = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xBA, 2))[0] + self._MC = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xBC, 2))[0] + self._MD = unp('>h', self._bmp_i2c.readfrom_mem(_bmp_addr, 0xBE, 2))[0] + + # settings to be adjusted by user + self.oversample_setting = 3 + self.baseline = 101325.0 + + # output raw + self.UT_raw = None + self.B5_raw = None + self.MSB_raw = None + self.LSB_raw = None + self.XLSB_raw = None + self.gauge = self.makegauge() # Generator instance + for _ in range(128): + next(self.gauge) + time.sleep_ms(1) + + def compvaldump(self): + ''' + Returns a list of all compensation values + ''' + return [self._AC1, self._AC2, self._AC3, self._AC4, self._AC5, self._AC6, + self._B1, self._B2, self._MB, self._MC, self._MD, self.oversample_setting] + + # gauge raw + def makegauge(self): + ''' + Generator refreshing the raw measurments. + ''' + delays = (5, 8, 14, 25) + while True: + self._bmp_i2c.writeto_mem(self._bmp_addr, 0xF4, bytearray([0x2E])) + t_start = time.ticks_ms() + while (time.ticks_ms() - t_start) <= 5: # 5mS delay + yield None + try: + self.UT_raw = self._bmp_i2c.readfrom_mem(self._bmp_addr, 0xF6, 2) + except: + yield None + self._bmp_i2c.writeto_mem(self._bmp_addr, 0xF4, bytearray([0x34+(self.oversample_setting << 6)])) + t_pressure_ready = delays[self.oversample_setting] + t_start = time.ticks_ms() + while (time.ticks_ms() - t_start) <= t_pressure_ready: + yield None + try: + self.MSB_raw = self._bmp_i2c.readfrom_mem(self._bmp_addr, 0xF6, 1) + self.LSB_raw = self._bmp_i2c.readfrom_mem(self._bmp_addr, 0xF7, 1) + self.XLSB_raw = self._bmp_i2c.readfrom_mem(self._bmp_addr, 0xF8, 1) + except: + yield None + yield True + + def blocking_read(self): + if next(self.gauge) is not None: # Discard old data + pass + while next(self.gauge) is None: + pass + + @property + def oversample_sett(self): + return self.oversample_setting + + @oversample_sett.setter + def oversample_sett(self, value): + if value in range(4): + self.oversample_setting = value + else: + print('oversample_sett can only be 0, 1, 2 or 3, using 3 instead') + self.oversample_setting = 3 + + @property + def temperature(self): + ''' + Temperature in degree C. + ''' + next(self.gauge) + try: + UT = unp('>H', self.UT_raw)[0] + except: + return 0.0 + X1 = (UT-self._AC6)*self._AC5/2**15 + X2 = self._MC*2**11/(X1+self._MD) + self.B5_raw = X1+X2 + return (((X1+X2)+8)/2**4)/10 + + @property + def pressure(self): + ''' + Pressure in mbar. + ''' + next(self.gauge) + self.temperature # Populate self.B5_raw + try: + MSB = unp('B', self.MSB_raw)[0] + LSB = unp('B', self.LSB_raw)[0] + XLSB = unp('B', self.XLSB_raw)[0] + except: + return 0.0 + UP = ((MSB << 16)+(LSB << 8)+XLSB) >> (8-self.oversample_setting) + B6 = self.B5_raw-4000 + X1 = (self._B2*(B6**2/2**12))/2**11 + X2 = self._AC2*B6/2**11 + X3 = X1+X2 + B3 = ((int((self._AC1*4+X3)) << self.oversample_setting)+2)/4 + X1 = self._AC3*B6/2**13 + X2 = (self._B1*(B6**2/2**12))/2**16 + X3 = ((X1+X2)+2)/2**2 + B4 = abs(self._AC4)*(X3+32768)/2**15 + B7 = (abs(UP)-B3) * (50000 >> self.oversample_setting) + if B7 < 0x80000000: + pressure = (B7*2)/B4 + else: + pressure = (B7/B4)*2 + X1 = (pressure/2**8)**2 + X1 = (X1*3038)/2**16 + X2 = (-7357*pressure)/2**16 + return pressure+(X1+X2+3791)/2**4 + + @property + def altitude(self): + ''' + Altitude in m. + ''' + try: + p = -7990.0*math.log(self.pressure/self.baseline) + except: + p = 0.0 + return p diff --git a/examples/40-fm-tuner-rda5807/esp32-pinout-reference-wroom-devkit.png b/examples/40-fm-tuner-rda5807/esp32-pinout-reference-wroom-devkit.png new file mode 100644 index 0000000..4905a65 Binary files /dev/null and b/examples/40-fm-tuner-rda5807/esp32-pinout-reference-wroom-devkit.png differ diff --git a/examples/40-fm-tuner-rda5807/i2c_scan.py b/examples/40-fm-tuner-rda5807/i2c_scan.py new file mode 100644 index 0000000..40465da --- /dev/null +++ b/examples/40-fm-tuner-rda5807/i2c_scan.py @@ -0,0 +1,38 @@ +""" +I2C scanner + +Scan the I2C (Inter-Integrated Circuit) bus for connected +devices and print their addresses. This script is useful +for identifying I2C devices connected to your microcontroller. + +Authors: +- MicroPython +- Tomas Fryza + +Creation date: 2023-06-17 +Last modified: 2025-02-25 + +Scanning I2C... 7 device(s) detected +dec. hex. +16 0x10 -- rda5807 (sequential access / RDA5800 mode) +17 0x11 -- rda5807 (random access / RDA5807 mode !!!) +35 0x23 -- bh1750 (light sensor) +60 0x3c -- OLED (!!!) +96 0x60 -- rda5807 (TEA5767 compatible mode) +104 0x68 -- mpu6050 (accel/gyro/temp) +119 0x77 -- bmp180 (pressure/temperature !!!) +""" + +from machine import I2C +from machine import Pin + +# Init I2C using pins GP22 & GP21 (default I2C0 pins) +i2c = I2C(0, scl=Pin(22), sda=Pin(21), freq=400_000) + +print("Scanning I2C... ", end="") +addrs = i2c.scan() +print(f"{len(addrs)} device(s) detected") + +print("dec.\t hex.") +for addr in addrs: + print(f"{addr}\t {hex(addr)}") diff --git a/examples/40-fm-tuner-rda5807/rda5807m-arduino.png b/examples/40-fm-tuner-rda5807/rda5807m-arduino.png new file mode 100644 index 0000000..7fed37b Binary files /dev/null and b/examples/40-fm-tuner-rda5807/rda5807m-arduino.png differ diff --git a/examples/40-fm-tuner-rda5807/ssd1306.py b/examples/40-fm-tuner-rda5807/ssd1306.py new file mode 100644 index 0000000..9eaa7cc --- /dev/null +++ b/examples/40-fm-tuner-rda5807/ssd1306.py @@ -0,0 +1,157 @@ +# https://github.com/stlehmann/micropython-ssd1306/blob/master/ssd1306.py + +# MicroPython SSD1306 OLED driver, I2C and SPI interfaces + +from micropython import const +import framebuf + + +# register definitions +SET_CONTRAST = const(0x81) +SET_ENTIRE_ON = const(0xA4) +SET_NORM_INV = const(0xA6) +SET_DISP = const(0xAE) +SET_MEM_ADDR = const(0x20) +SET_COL_ADDR = const(0x21) +SET_PAGE_ADDR = const(0x22) +SET_DISP_START_LINE = const(0x40) +SET_SEG_REMAP = const(0xA0) +SET_MUX_RATIO = const(0xA8) +SET_COM_OUT_DIR = const(0xC0) +SET_DISP_OFFSET = const(0xD3) +SET_COM_PIN_CFG = const(0xDA) +SET_DISP_CLK_DIV = const(0xD5) +SET_PRECHARGE = const(0xD9) +SET_VCOM_DESEL = const(0xDB) +SET_CHARGE_PUMP = const(0x8D) + +# Subclassing FrameBuffer provides support for graphics primitives +# http://docs.micropython.org/en/latest/pyboard/library/framebuf.html +class SSD1306(framebuf.FrameBuffer): + def __init__(self, width, height, external_vcc): + self.width = width + self.height = height + self.external_vcc = external_vcc + self.pages = self.height // 8 + self.buffer = bytearray(self.pages * self.width) + super().__init__(self.buffer, self.width, self.height, framebuf.MONO_VLSB) + self.init_display() + + def init_display(self): + for cmd in ( + SET_DISP | 0x00, # off + # address setting + SET_MEM_ADDR, + 0x00, # horizontal + # resolution and layout + SET_DISP_START_LINE | 0x00, + SET_SEG_REMAP | 0x01, # column addr 127 mapped to SEG0 + SET_MUX_RATIO, + self.height - 1, + SET_COM_OUT_DIR | 0x08, # scan from COM[N] to COM0 + SET_DISP_OFFSET, + 0x00, + SET_COM_PIN_CFG, + 0x02 if self.width > 2 * self.height else 0x12, + # timing and driving scheme + SET_DISP_CLK_DIV, + 0x80, + SET_PRECHARGE, + 0x22 if self.external_vcc else 0xF1, + SET_VCOM_DESEL, + 0x30, # 0.83*Vcc + # display + SET_CONTRAST, + 0xFF, # maximum + SET_ENTIRE_ON, # output follows RAM contents + SET_NORM_INV, # not inverted + # charge pump + SET_CHARGE_PUMP, + 0x10 if self.external_vcc else 0x14, + SET_DISP | 0x01, + ): # on + self.write_cmd(cmd) + self.fill(0) + self.show() + + def poweroff(self): + self.write_cmd(SET_DISP | 0x00) + + def poweron(self): + self.write_cmd(SET_DISP | 0x01) + + def contrast(self, contrast): + self.write_cmd(SET_CONTRAST) + self.write_cmd(contrast) + + def invert(self, invert): + self.write_cmd(SET_NORM_INV | (invert & 1)) + + def show(self): + x0 = 0 + x1 = self.width - 1 + if self.width == 64: + # displays with width of 64 pixels are shifted by 32 + x0 += 32 + x1 += 32 + self.write_cmd(SET_COL_ADDR) + self.write_cmd(x0) + self.write_cmd(x1) + self.write_cmd(SET_PAGE_ADDR) + self.write_cmd(0) + self.write_cmd(self.pages - 1) + self.write_data(self.buffer) + + +class SSD1306_I2C(SSD1306): + def __init__(self, width, height, i2c, addr=0x3C, external_vcc=False): + self.i2c = i2c + self.addr = addr + self.temp = bytearray(2) + self.write_list = [b"\x40", None] # Co=0, D/C#=1 + super().__init__(width, height, external_vcc) + + def write_cmd(self, cmd): + self.temp[0] = 0x80 # Co=1, D/C#=0 + self.temp[1] = cmd + self.i2c.writeto(self.addr, self.temp) + + def write_data(self, buf): + self.write_list[1] = buf + self.i2c.writevto(self.addr, self.write_list) + + +class SSD1306_SPI(SSD1306): + def __init__(self, width, height, spi, dc, res, cs, external_vcc=False): + self.rate = 10 * 1024 * 1024 + dc.init(dc.OUT, value=0) + res.init(res.OUT, value=0) + cs.init(cs.OUT, value=1) + self.spi = spi + self.dc = dc + self.res = res + self.cs = cs + import time + + self.res(1) + time.sleep_ms(1) + self.res(0) + time.sleep_ms(10) + self.res(1) + super().__init__(width, height, external_vcc) + + def write_cmd(self, cmd): + self.spi.init(baudrate=self.rate, polarity=0, phase=0) + self.cs(1) + self.dc(0) + self.cs(0) + self.spi.write(bytearray([cmd])) + self.cs(1) + + def write_data(self, buf): + self.spi.init(baudrate=self.rate, polarity=0, phase=0) + self.cs(1) + self.dc(1) + self.cs(0) + self.spi.write(buf) + self.cs(1) \ No newline at end of file