From 6fc4431976195d58e98f5759eedffcba5b469beb Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Tue, 3 Sep 2024 15:28:40 +0100 Subject: [PATCH 1/7] Changes for dfr0300 EC sensor --- mqtt_io/modules/sensor/__init__.py | 7 +++++- mqtt_io/modules/sensor/bme680.py | 18 ++++++++------- mqtt_io/modules/sensor/hcsr04.py | 4 +++- mqtt_io/modules/sensor/mock.py | 8 ++++--- mqtt_io/modules/sensor/pms5003.py | 35 +++++++++++++++++++----------- mqtt_io/server.py | 2 +- 6 files changed, 47 insertions(+), 27 deletions(-) diff --git a/mqtt_io/modules/sensor/__init__.py b/mqtt_io/modules/sensor/__init__.py index fa999929..eabd747e 100644 --- a/mqtt_io/modules/sensor/__init__.py +++ b/mqtt_io/modules/sensor/__init__.py @@ -7,6 +7,8 @@ from concurrent.futures import ThreadPoolExecutor from typing import Any +from mqtt_io.events import EventBus + from ...types import ConfigType, SensorValueType @@ -36,13 +38,16 @@ def setup_module(self) -> None: in `self.config`. """ - def setup_sensor(self, sens_conf: ConfigType) -> None: + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: """ Called on initialisation of each reading type of the Sensor module during the startup phase. The `sens_conf` passed in here is the sensor's entry in the `sensor_inputs` section of the config file. + + The `event_bus` is the system event bus so that it is possible to track and respond + to other events, such as other sensor readings. """ def cleanup(self) -> None: diff --git a/mqtt_io/modules/sensor/bme680.py b/mqtt_io/modules/sensor/bme680.py index fe14b5ef..367cca7c 100644 --- a/mqtt_io/modules/sensor/bme680.py +++ b/mqtt_io/modules/sensor/bme680.py @@ -4,13 +4,15 @@ from typing import cast +from mqtt_io.events import EventBus + from ...types import CerberusSchemaType, ConfigType, SensorValueType from . import GenericSensor REQUIREMENTS = ("smbus2", "bme680") CONFIG_SCHEMA = { - "i2c_bus_num": {"type": 'integer', "required": False, "empty": False}, - "chip_addr": {"type": 'integer', "required": True, "empty": False}, + "i2c_bus_num": {"type": "integer", "required": False, "empty": False}, + "chip_addr": {"type": "integer", "required": True, "empty": False}, } @@ -21,15 +23,15 @@ class Sensor(GenericSensor): SENSOR_SCHEMA: CerberusSchemaType = { "type": { - "type": 'string', + "type": "string", "required": False, - "default": 'temperature', - "allowed": ['temperature', 'humidity', 'pressure'], + "default": "temperature", + "allowed": ["temperature", "humidity", "pressure"], }, "oversampling": { - "type": 'string', + "type": "string", "required": False, - "allowed": ['none', '1x', '2x', '4x', '8x', '16x'], + "allowed": ["none", "1x", "2x", "4x", "8x", "16x"], }, } @@ -53,7 +55,7 @@ def setup_module(self) -> None: "16x": bme680.OS_16X, } - def setup_sensor(self, sens_conf: ConfigType) -> None: + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: sens_type: str = sens_conf["type"] if "oversampling" in sens_conf: set_oversampling = getattr(self.sensor, f"set_{sens_type}_oversample") diff --git a/mqtt_io/modules/sensor/hcsr04.py b/mqtt_io/modules/sensor/hcsr04.py index 5c6d434c..bdaf7a5a 100644 --- a/mqtt_io/modules/sensor/hcsr04.py +++ b/mqtt_io/modules/sensor/hcsr04.py @@ -6,6 +6,8 @@ from statistics import mean from typing import Any, Dict, List, Optional +from mqtt_io.events import EventBus + from ...types import CerberusSchemaType, ConfigType, SensorValueType from . import GenericSensor @@ -123,7 +125,7 @@ def setup_module(self) -> None: self.gpio = GPIO self.sensors: Dict[str, HCSR04] = {} - def setup_sensor(self, sens_conf: ConfigType) -> None: + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: sensor = HCSR04(gpio=self.gpio, **sens_conf) self.sensors[sensor.name] = sensor diff --git a/mqtt_io/modules/sensor/mock.py b/mqtt_io/modules/sensor/mock.py index fb2b8677..18a3d68c 100644 --- a/mqtt_io/modules/sensor/mock.py +++ b/mqtt_io/modules/sensor/mock.py @@ -4,11 +4,13 @@ from unittest.mock import Mock +from mqtt_io.events import EventBus + from ...types import ConfigType, SensorValueType from . import GenericSensor REQUIREMENTS = () -CONFIG_SCHEMA = {"test": {"type": 'boolean', "required": False, "default": False}} +CONFIG_SCHEMA = {"test": {"type": "boolean", "required": False, "default": False}} # pylint: disable=useless-super-delegation @@ -26,8 +28,8 @@ def __init__(self, config: ConfigType): def setup_module(self) -> None: return super().setup_module() - def setup_sensor(self, sens_conf: ConfigType) -> None: - return super().setup_sensor(sens_conf) + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: + return super().setup_sensor(sens_conf, event_bus) def get_value(self, sens_conf: ConfigType) -> SensorValueType: return super().get_value(sens_conf) diff --git a/mqtt_io/modules/sensor/pms5003.py b/mqtt_io/modules/sensor/pms5003.py index 506d05a2..846535ea 100644 --- a/mqtt_io/modules/sensor/pms5003.py +++ b/mqtt_io/modules/sensor/pms5003.py @@ -9,7 +9,7 @@ REQUIREMENTS = ("plantower",) CONFIG_SCHEMA: CerberusSchemaType = { - "serial_port": {"type": 'string', "required": True, "empty": False}, + "serial_port": {"type": "string", "required": True, "empty": False}, } @@ -20,33 +20,42 @@ class Sensor(GenericSensor): SENSOR_SCHEMA: CerberusSchemaType = { "type": { - "type": 'string', + "type": "string", "required": False, "empty": False, - "default": 'pm25_std', - "allowed": - ['pm10_cf1', 'pm25_cf1','pm100_cf1', - 'pm10_std','pm25_std','pm100_std', - 'gr03um','gr05um','gr10um', - 'gr25um','gr50um','gr100um'], + "default": "pm25_std", + "allowed": [ + "pm10_cf1", + "pm25_cf1", + "pm100_cf1", + "pm10_std", + "pm25_std", + "pm100_std", + "gr03um", + "gr05um", + "gr10um", + "gr25um", + "gr50um", + "gr100um", + ], } } def setup_module(self) -> None: # pylint: disable=import-outside-toplevel,import-error - import plantower # type: ignore + import plantower # type: ignore self.serial_port = self.config["serial_port"] self.sensor = plantower.Plantower(port=self.serial_port) self.sensor.mode_change(plantower.PMS_PASSIVE_MODE) self.sensor.set_to_wakeup() - time.sleep(30) #give fan time to stabilize readings + time.sleep(30) # give fan time to stabilize readings def get_value(self, sens_conf: ConfigType) -> SensorValueType: """ Get the particulate data from the sensor """ - #turn sensor off if interval between readings is >= 2 minutes + # turn sensor off if interval between readings is >= 2 minutes sleep_sensor = sens_conf["interval"] >= 120 if sleep_sensor: self.sensor.set_to_wakeup() @@ -69,8 +78,8 @@ def get_value(self, sens_conf: ConfigType) -> SensorValueType: "gr10um": result.gr10um, "gr25um": result.gr25um, "gr50um": result.gr50um, - "gr100u": result.gr100um - }[sens_type], + "gr100u": result.gr100um, + }[sens_type], ) def cleanup(self) -> None: diff --git a/mqtt_io/server.py b/mqtt_io/server.py index 259f398c..ecfd7a9a 100644 --- a/mqtt_io/server.py +++ b/mqtt_io/server.py @@ -628,7 +628,7 @@ async def publish_sensor_callback(event: SensorReadEvent) -> None: ) self.sensor_input_configs[sens_conf["name"]] = sens_conf - sensor_module.setup_sensor(sens_conf) + sensor_module.setup_sensor(sens_conf, self.event_bus) # Use default args to the function to get around the late binding closures async def poll_sensor( From e7bfb9998752e015396bb4f51360a3eba8b41717 Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Tue, 3 Sep 2024 17:23:55 +0100 Subject: [PATCH 2/7] Add missing files --- mqtt_io/modules/sensor/dfr0300.py | 210 ++++++++++++++ mqtt_io/modules/sensor/drivers/__init__.py | 0 .../modules/sensor/drivers/dfr0566_driver.py | 257 ++++++++++++++++++ 3 files changed, 467 insertions(+) create mode 100644 mqtt_io/modules/sensor/dfr0300.py create mode 100644 mqtt_io/modules/sensor/drivers/__init__.py create mode 100644 mqtt_io/modules/sensor/drivers/dfr0566_driver.py diff --git a/mqtt_io/modules/sensor/dfr0300.py b/mqtt_io/modules/sensor/dfr0300.py new file mode 100644 index 00000000..c14bb96a --- /dev/null +++ b/mqtt_io/modules/sensor/dfr0300.py @@ -0,0 +1,210 @@ +""" +DFRobot Gravity DFR0300 Electrical Conductivity Sensor + +Example config (including optional temperature sensor): + +sensor_modules: + - name: aht20_temp + module: aht20 + - name: dfr0300 + module: dfr0300 + +sensor_inputs: + - name: temperature + module: aht20_temp + type: temperature + interval: 10 + digits: 4 + + - name: ec + module: dfr0300 + pin: 0 + tempsensor: temperature + # Specify temperature if no temperature sensor is configured + #temperature: 25.0 + interval: 10 + digits: 4 + + +""" + +import json +import logging +import os + +from typing import Tuple + +from mqtt_io.events import EventBus, SensorReadEvent +from mqtt_io.exceptions import RuntimeConfigError + +from ...types import CerberusSchemaType, ConfigType, PinType, SensorValueType +from . import GenericSensor + +_LOG = logging.getLogger(__name__) + +REQUIREMENTS = ("smbus",) +CONFIG_SCHEMA: CerberusSchemaType = { + "i2c_bus_num": {"type": "integer", "required": False, "empty": False, "default": 1}, + "chip_addr": { + "type": "integer", + "required": False, + "empty": False, + "default": 0x10, + }, +} + +ANALOG_PINS = [0, 1, 2, 3] +CALIBRATION_FILE = "ec_config.json" +CALIBRATION_FILE_ENCODING = "ascii" +INITIAL_KVALUE = 1.0 +DEFAULT_TEMPERATURE = 25.0 +TEMPSENSOR_ID = "tempsensor" +TEMPERATURE_ID = "temperature" + + +# pylint: disable=too-many-instance-attributes +class Sensor(GenericSensor): + """ + Implementation of Sensor class for the DFR0300 Electrical Conductivity Sensor + + """ + + SENSOR_SCHEMA: CerberusSchemaType = { + "pin": { + "type": "integer", + "required": True, + "empty": False, + "allowed": ANALOG_PINS, + }, + TEMPSENSOR_ID: { + "type": "string", + "required": False, + "empty": False, + }, + TEMPERATURE_ID: { + "type": "float", + "required": False, + "empty": False, + }, + } + + def setup_module(self) -> None: + # pylint: disable=import-outside-toplevel,import-error + from .drivers.dfr0566_driver import ( + DFRobotExpansionBoardIIC, + ) # type: ignore + + self.board = DFRobotExpansionBoardIIC( + self.config["i2c_bus_num"], self.config["chip_addr"] + ) # type: ignore + self.board.setup() + self.board.set_adc_enable() + + self.pin2channel = { + 0: self.board.A0, + 1: self.board.A1, + 2: self.board.A2, + 3: self.board.A3, + } + + self.kvalue = INITIAL_KVALUE + self.kvalue_low = INITIAL_KVALUE + self.kvalue_mid = INITIAL_KVALUE + self.kvalue_high = INITIAL_KVALUE + self.calibration_file = os.path.abspath(CALIBRATION_FILE) + if os.path.exists(self.calibration_file): + self.kvalue_low, self.kvalue_mid, self.kvalue_high = self.read_calibration() + + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: + """ + Setup the sensor module + """ + if TEMPSENSOR_ID in sens_conf and TEMPERATURE_ID in sens_conf: + raise RuntimeConfigError( + "Cannot specify both temperature sensor and temperature value" + ) + + pin: PinType = sens_conf["pin"] + try: + # pylint: disable=attribute-defined-outside-init + self.channel = self.pin2channel[int(pin)] + except KeyError as exc: + raise RuntimeConfigError( + "pin '%s' was not configured to return a valid value" % pin + ) from exc + + # pylint: disable=attribute-defined-outside-init + self.temperature = DEFAULT_TEMPERATURE + if TEMPERATURE_ID in sens_conf: + self.temperature = sens_conf[TEMPERATURE_ID] + _LOG.info("dfr0300: Set temperature to %f", self.temperature) + return + + if TEMPSENSOR_ID not in sens_conf: + _LOG.info("dfr0300: No temperature sensor configured") + return + + async def on_sensor_read(event: SensorReadEvent) -> None: + """Callback for sensor read event + Sets self.temperature from the temperature sensor + """ + if ( + event.sensor_name == sens_conf[TEMPSENSOR_ID] + and event.value is not None + ): + self.temperature = event.value + + event_bus.subscribe(SensorReadEvent, on_sensor_read) + + def read_calibration(self) -> Tuple[float, float, float]: + """Read calibrated values from json file. + { + "kvalue_low": 1.0, + "kvalue_mid": 1.0, + "kvalue_high": 1.0 + } + + """ + if os.path.exists(self.calibration_file): + with open( + self.calibration_file, "r", encoding=CALIBRATION_FILE_ENCODING + ) as file_handle: + try: + data = json.load(file_handle) + except json.decoder.JSONDecodeError: + raise FileNotFoundError( + f"Calibration file {self.calibration_file} is not valid JSON" + ) from None + kvalue_low = float(data["kvalue_low"]) + kvalue_mid = float(data["kvalue_mid"]) + kvalue_high = float(data["kvalue_high"]) + return (kvalue_low, kvalue_mid, kvalue_high) + raise FileNotFoundError(f"Calibration file {self.calibration_file} not found") + + @staticmethod + def calc_raw_ec(voltage: float) -> float: + """Convert voltage to raw EC""" + return 1000 * voltage / 820.0 / 200.0 + + def ec_from_voltage(self, voltage: float, temperature: float) -> float: + """Convert voltage to EC with temperature compensation""" + # pylint: disable=attribute-defined-outside-init + raw_ec = self.calc_raw_ec(voltage) + value_temp = raw_ec * self.kvalue + if value_temp > 5.0: + self.kvalue = self.kvalue_high + elif value_temp >= 2.0: + self.kvalue = self.kvalue_mid + elif value_temp < 2.0: + self.kvalue = self.kvalue_low + value = raw_ec * self.kvalue + return value / (1.0 + 0.0185 * (temperature - 25.0)) + + def get_value(self, _sens_conf: ConfigType) -> SensorValueType: + """ + Get the EC from the sensor + """ + voltage = self.board.get_adc_value(self.channel) + ec_value = self.ec_from_voltage(voltage, self.temperature) + # _LOG.info("Temperature:%.2f ^C EC:%.2f ms/cm", self.temperature, ec_value) + return ec_value diff --git a/mqtt_io/modules/sensor/drivers/__init__.py b/mqtt_io/modules/sensor/drivers/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/mqtt_io/modules/sensor/drivers/dfr0566_driver.py b/mqtt_io/modules/sensor/drivers/dfr0566_driver.py new file mode 100644 index 00000000..3149a22e --- /dev/null +++ b/mqtt_io/modules/sensor/drivers/dfr0566_driver.py @@ -0,0 +1,257 @@ +# -*- coding:utf-8 -*- + +""" + Adapted from the below by @linucks + + @file DFRobot_RaspberryPi_Expansion_Board.py + @brief This RaspberryPi expansion board can communicate with RaspberryPi via I2C. + It has 10 GPIOs, 1 SPI, 4 I2Cs and 1 uart. + @copyright Copyright (c) 2010 DFRobot Co.Ltd (http://www.dfrobot.com) + @license The MIT License (MIT) + @author Frank(jiehan.guo@dfrobot.com) + @version V1.0 + @date 2019-3-28 + @url https://github.com/DFRobot/DFRobot_RaspberryPi_Expansion_Board +""" +import abc +import logging +import time +from typing import List + +BOARD_SETUP_TRIES = 3 +BOARD_SETUP_TIMEOUT = 2 +PMW_CHANNELS = 4 + +_LOG = logging.getLogger(__name__) + + +class DFRobotExpansionBoard(abc.ABC): + """Base class for Expansion Board functionality.""" + + _REG_SLAVE_ADDR = 0x00 + _REG_PID = 0x01 + _REG_VID = 0x02 + _REG_PWM_CONTROL = 0x03 + _REG_PWM_FREQ = 0x04 + _REG_PWM_DUTY1 = 0x06 + _REG_PWM_DUTY2 = 0x08 + _REG_PWM_DUTY3 = 0x0A + _REG_PWM_DUTY4 = 0x0C + _REG_ADC_CTRL = 0x0E + _REG_ADC_VAL1 = 0x0F + _REG_ADC_VAL2 = 0x11 + _REG_ADC_VAL3 = 0x13 + _REG_ADC_VAL4 = 0x15 + + _REG_DEF_PID = 0xDF + _REG_DEF_VID = 0x10 + + """ Enum board Analog channels """ + A0 = 0x00 + A1 = 0x01 + A2 = 0x02 + A3 = 0x03 + + """ Board status """ + STA_OK = 0x00 + STA_ERR = 0x01 + STA_ERR_DEVICE_NOT_DETECTED = 0x02 + STA_ERR_SOFT_VERSION = 0x03 + STA_ERR_PARAMETER = 0x04 + + """Last operation status: use this variable to determine the result of a function call. """ + last_operate_status = STA_OK + + @abc.abstractmethod + def _write_bytes(self, reg: int, buf: List[int]) -> None: + pass + + @abc.abstractmethod + def _read_bytes(self, reg: int, length: int) -> List[int]: + pass + + def __init__(self, addr: int) -> None: + self._addr = addr + self._is_pwm_enable = False + + def begin(self, disable_pmw: bool = False, disable_adc: bool = False) -> int: + """ + Board begin + return: Board status + """ + pid = self._read_bytes(self._REG_PID, 1) + vid = self._read_bytes(self._REG_VID, 1) + if self.last_operate_status == self.STA_OK: + if pid[0] != self._REG_DEF_PID: + self.last_operate_status = self.STA_ERR_DEVICE_NOT_DETECTED + elif vid[0] != self._REG_DEF_VID: + self.last_operate_status = self.STA_ERR_SOFT_VERSION + else: + if disable_pmw: + self.set_pwm_disable() + if disable_adc: + self.set_adc_disable() + return self.last_operate_status + + def set_addr(self, addr: int) -> None: + """ + Set board controler address, reboot module to make it effective + addr: int Address to set, range in 1 to 127 + """ + if addr < 1 or addr > 127: + self.last_operate_status = self.STA_ERR_PARAMETER + return + self._write_bytes(self._REG_SLAVE_ADDR, [addr]) + + def setup(self) -> None: + """Run the board setup.""" + count = 0 + while self.begin() != self.STA_OK: + count += 1 + if count > BOARD_SETUP_TRIES: + raise RuntimeError( + "Failed to initialise board: %s" % board_status_str(self) + ) + time.sleep(BOARD_SETUP_TIMEOUT) + + def set_adc_enable(self) -> None: + """ + Enable the ADC + """ + self._write_bytes(self._REG_ADC_CTRL, [0x01]) + + def set_adc_disable(self) -> None: + """ + Disable the ADC + """ + self._write_bytes(self._REG_ADC_CTRL, [0x00]) + + def get_adc_value(self, chan: int) -> float: + """ + Return the ADC value for the given channel. + """ + rslt = self._read_bytes(self._REG_ADC_VAL1 + chan * 2, 2) + return (rslt[0] << 8) | rslt[1] + + def set_pwm_enable(self) -> None: + """ + Set pwm enable, pwm channel need external power + """ + self._write_bytes(self._REG_PWM_CONTROL, [0x01]) + if self.last_operate_status == self.STA_OK: + self._is_pwm_enable = True + time.sleep(0.01) + + def set_pwm_disable(self) -> None: + """ + Disable the PWM + """ + self._write_bytes(self._REG_PWM_CONTROL, [0x00]) + if self.last_operate_status == self.STA_OK: + self._is_pwm_enable = False + time.sleep(0.01) + + def set_pwm_frequency(self, freq: int) -> None: + """ + Set PWM frequency: + freq: int Frequency to set, in range 1 - 1000 + """ + if freq < 1 or freq > 1000: + self.last_operate_status = self.STA_ERR_PARAMETER + return + is_pwm_enable = self._is_pwm_enable + self.set_pwm_disable() + self._write_bytes(self._REG_PWM_FREQ, [freq >> 8, freq & 0xFF]) + time.sleep(0.01) + if is_pwm_enable: + self.set_pwm_enable() + + def set_pwm_duty(self, chan: int, duty: float) -> None: + """ + Set selected channel duty: + chan: Channel to set, in range 0 - 3 + duty: Duty to set, in range 0.0 to 100.0 + """ + if duty < 0 or duty > 100: + self.last_operate_status = self.STA_ERR_PARAMETER + return + self._write_bytes( + self._REG_PWM_DUTY1 + chan * 2, [int(duty), int((duty * 10) % 10)] + ) + + +class DFRobotExpansionBoardIIC(DFRobotExpansionBoard): + """Class for IIC communication with Expansion Board.""" + + def __init__(self, bus_id: int, addr: int) -> None: + """ + @param bus_id: int Which bus to operate + @oaram addr: int Board controler address + """ + # pylint: disable=import-outside-toplevel,import-error + import smbus # type: ignore + + self._bus = smbus.SMBus(bus_id) + super().__init__(addr) + + def _write_bytes(self, reg: int, buf: List[int]) -> None: + self.last_operate_status = self.STA_ERR_DEVICE_NOT_DETECTED + try: + self._bus.write_i2c_block_data(self._addr, reg, buf) + self.last_operate_status = self.STA_OK + except Exception: # pylint: disable=broad-except + _LOG.warning("DFRobotExpansionBoardIIC I2C write error") + + def _read_bytes(self, reg: int, length: int) -> List[int]: + self.last_operate_status = self.STA_ERR_DEVICE_NOT_DETECTED + try: + rslt: List[int] = self._bus.read_i2c_block_data(self._addr, reg, length) + self.last_operate_status = self.STA_OK + return rslt + except Exception: # pylint: disable=broad-except + _LOG.warning("DFRobotExpansionBoardIIC I2C read error") + return [0] * length + + +class DFRobotExpansionBoardServo: + """ + board: DFRobot_Expansion_Board + Board instance to operate servo, test servo: https://www.dfrobot.com/product-255.html + + Warning: servo must connect to pwm channel, otherwise may destory Pi IO + """ + + def __init__(self, board: DFRobotExpansionBoard) -> None: + """Set the board instance.""" + self._board = board + + def begin(self) -> None: + """ + Board servo begin + """ + self._board.set_pwm_enable() + self._board.set_pwm_frequency(50) + for channel in range(PMW_CHANNELS): + self._board.set_pwm_duty(channel, 0) + + def move(self, channel_id: int, angle: int) -> None: + """ + Move the servo to the given angle. + channel_id: int Servos to set in range 0 to 3 + angle: int Angle to move, in range 0 to 180 + """ + if 0 <= angle <= 180: + self._board.set_pwm_duty( + channel_id, (0.5 + (float(angle) / 90.0)) / 20 * 100 + ) + + +def board_status_str(board: DFRobotExpansionBoard) -> str: + """Return board status as string.""" + return { + board.STA_OK: "STA_OK", + board.STA_ERR: "STA_ERR", + board.STA_ERR_DEVICE_NOT_DETECTED: "STA_ERR_DEVICE_NOT_DETECTED", + board.STA_ERR_PARAMETER: "STA_ERR_PARAMETER", + board.STA_ERR_SOFT_VERSION: "STA_ERR_SOFT_VERSION", + }.get(board.last_operate_status, "unknown error") From 92c6805bbec96800938989f9ccc4f638d3b71e13 Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Tue, 3 Sep 2024 17:27:31 +0100 Subject: [PATCH 3/7] Add missing parameter --- mqtt_io/modules/sensor/flowsensor.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/mqtt_io/modules/sensor/flowsensor.py b/mqtt_io/modules/sensor/flowsensor.py index 392d0e42..656e4c92 100644 --- a/mqtt_io/modules/sensor/flowsensor.py +++ b/mqtt_io/modules/sensor/flowsensor.py @@ -33,6 +33,8 @@ """ from typing import Dict + +from mqtt_io.events import EventBus from ...types import CerberusSchemaType, ConfigType, SensorValueType from . import GenericSensor @@ -110,7 +112,7 @@ def setup_module(self) -> None: self.gpiozero = gpiozero self.sensors: Dict[str, FLOWSENSOR] = {} - def setup_sensor(self, sens_conf: ConfigType) -> None: + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: sensor = FLOWSENSOR( gpiozero=self.gpiozero, name=sens_conf["name"], pin=sens_conf["pin"] ) From 056fd4c9aa39032f4619f6f8ff074d1c4d9dc7aa Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Tue, 3 Sep 2024 17:30:04 +0100 Subject: [PATCH 4/7] Fix function call --- mqtt_io/modules/sensor/frequencycounter.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/mqtt_io/modules/sensor/frequencycounter.py b/mqtt_io/modules/sensor/frequencycounter.py index dcfbb38e..9466cddc 100644 --- a/mqtt_io/modules/sensor/frequencycounter.py +++ b/mqtt_io/modules/sensor/frequencycounter.py @@ -18,6 +18,8 @@ """ from typing import Dict + +from mqtt_io.events import EventBus from ...types import CerberusSchemaType, ConfigType, SensorValueType from . import GenericSensor @@ -30,7 +32,7 @@ class FREQUENCYCOUNTER: Multiple instances support multiple sensors on different pins """ - def __init__(self, gpiozero, name: str, pin: int) -> None: # type: ignore[no-untyped-def] + def __init__(self, gpiozero, name: str, pin: int) -> None: # type: ignore[no-untyped-def] self.name = name self.pin = gpiozero.DigitalInputDevice(pin) self.pin.when_activated = self.count_pulse @@ -65,15 +67,15 @@ class Sensor(GenericSensor): SENSOR_SCHEMA: CerberusSchemaType = { "pin": { - "type": 'integer', + "type": "integer", "required": True, "empty": False, }, "interval": { - "type": 'integer', + "type": "integer", "required": True, "empty": False, - } + }, } def setup_module(self) -> None: @@ -83,7 +85,7 @@ def setup_module(self) -> None: self.gpiozero = gpiozero self.sensors: Dict[str, FREQUENCYCOUNTER] = {} - def setup_sensor(self, sens_conf: ConfigType) -> None: + def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: sensor = FREQUENCYCOUNTER( gpiozero=self.gpiozero, name=sens_conf["name"], pin=sens_conf["pin"] ) From b580c6c73aaa340c9eeada987f7d1009c38e30e0 Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Tue, 3 Sep 2024 18:23:28 +0100 Subject: [PATCH 5/7] Remove mid point reading --- mqtt_io/modules/sensor/dfr0300.py | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/mqtt_io/modules/sensor/dfr0300.py b/mqtt_io/modules/sensor/dfr0300.py index c14bb96a..f8ce5d1f 100644 --- a/mqtt_io/modules/sensor/dfr0300.py +++ b/mqtt_io/modules/sensor/dfr0300.py @@ -109,11 +109,10 @@ def setup_module(self) -> None: self.kvalue = INITIAL_KVALUE self.kvalue_low = INITIAL_KVALUE - self.kvalue_mid = INITIAL_KVALUE self.kvalue_high = INITIAL_KVALUE self.calibration_file = os.path.abspath(CALIBRATION_FILE) if os.path.exists(self.calibration_file): - self.kvalue_low, self.kvalue_mid, self.kvalue_high = self.read_calibration() + self.kvalue_low, self.kvalue_high = self.read_calibration() def setup_sensor(self, sens_conf: ConfigType, event_bus: EventBus) -> None: """ @@ -156,11 +155,10 @@ async def on_sensor_read(event: SensorReadEvent) -> None: event_bus.subscribe(SensorReadEvent, on_sensor_read) - def read_calibration(self) -> Tuple[float, float, float]: + def read_calibration(self) -> Tuple[float, float]: """Read calibrated values from json file. { "kvalue_low": 1.0, - "kvalue_mid": 1.0, "kvalue_high": 1.0 } @@ -176,9 +174,8 @@ def read_calibration(self) -> Tuple[float, float, float]: f"Calibration file {self.calibration_file} is not valid JSON" ) from None kvalue_low = float(data["kvalue_low"]) - kvalue_mid = float(data["kvalue_mid"]) kvalue_high = float(data["kvalue_high"]) - return (kvalue_low, kvalue_mid, kvalue_high) + return (kvalue_low, kvalue_high) raise FileNotFoundError(f"Calibration file {self.calibration_file} not found") @staticmethod @@ -191,10 +188,8 @@ def ec_from_voltage(self, voltage: float, temperature: float) -> float: # pylint: disable=attribute-defined-outside-init raw_ec = self.calc_raw_ec(voltage) value_temp = raw_ec * self.kvalue - if value_temp > 5.0: + if value_temp > 2.5: self.kvalue = self.kvalue_high - elif value_temp >= 2.0: - self.kvalue = self.kvalue_mid elif value_temp < 2.0: self.kvalue = self.kvalue_low value = raw_ec * self.kvalue From 6afa9242ef3249404913031975d4632df40bfb26 Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Wed, 4 Sep 2024 11:47:57 +0100 Subject: [PATCH 6/7] Better logging and use constants --- mqtt_io/modules/sensor/dfr0300.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/mqtt_io/modules/sensor/dfr0300.py b/mqtt_io/modules/sensor/dfr0300.py index f8ce5d1f..e24052c9 100644 --- a/mqtt_io/modules/sensor/dfr0300.py +++ b/mqtt_io/modules/sensor/dfr0300.py @@ -60,6 +60,8 @@ DEFAULT_TEMPERATURE = 25.0 TEMPSENSOR_ID = "tempsensor" TEMPERATURE_ID = "temperature" +RES2 = 820.0 +ECREF = 200.0 # pylint: disable=too-many-instance-attributes @@ -175,13 +177,14 @@ def read_calibration(self) -> Tuple[float, float]: ) from None kvalue_low = float(data["kvalue_low"]) kvalue_high = float(data["kvalue_high"]) + _LOG.debug("Read calibration values: %f, %f", kvalue_low, kvalue_high) return (kvalue_low, kvalue_high) raise FileNotFoundError(f"Calibration file {self.calibration_file} not found") @staticmethod def calc_raw_ec(voltage: float) -> float: """Convert voltage to raw EC""" - return 1000 * voltage / 820.0 / 200.0 + return 1000 * voltage / RES2 / ECREF def ec_from_voltage(self, voltage: float, temperature: float) -> float: """Convert voltage to EC with temperature compensation""" From f68a2e6f14470148c1e96dcf0528f6b098cf4d18 Mon Sep 17 00:00:00 2001 From: Jens Thomas Date: Mon, 24 Mar 2025 15:02:33 +0000 Subject: [PATCH 7/7] Better doc & samples config --- mqtt_io/modules/sensor/dfr0300.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/mqtt_io/modules/sensor/dfr0300.py b/mqtt_io/modules/sensor/dfr0300.py index e24052c9..595b42cc 100644 --- a/mqtt_io/modules/sensor/dfr0300.py +++ b/mqtt_io/modules/sensor/dfr0300.py @@ -10,16 +10,20 @@ module: dfr0300 sensor_inputs: - - name: temperature + - name: temp_aht20 module: aht20_temp type: temperature interval: 10 digits: 4 + ha_discovery: + name: Temperature + device_class: temperature - name: ec module: dfr0300 pin: 0 - tempsensor: temperature + # Must match the name of the temperature sensor + tempsensor: temp_aht20 # Specify temperature if no temperature sensor is configured #temperature: 25.0 interval: 10 @@ -67,7 +71,8 @@ # pylint: disable=too-many-instance-attributes class Sensor(GenericSensor): """ - Implementation of Sensor class for the DFR0300 Electrical Conductivity Sensor + Implementation of Sensor class for the DFRobot DFR0300 Electrical Conductivity Sensor + (Using the DFRobot DFR0566 RaspberryPi Expansion Board) """ @@ -158,7 +163,8 @@ async def on_sensor_read(event: SensorReadEvent) -> None: event_bus.subscribe(SensorReadEvent, on_sensor_read) def read_calibration(self) -> Tuple[float, float]: - """Read calibrated values from json file. + """Read calibrated values from json file with format: + { "kvalue_low": 1.0, "kvalue_high": 1.0