diff --git a/Firmware/RaspberryPi/backend-pi/Controller.py b/Firmware/RaspberryPi/backend-pi/Controller.py index abab960..4f7c2f1 100644 --- a/Firmware/RaspberryPi/backend-pi/Controller.py +++ b/Firmware/RaspberryPi/backend-pi/Controller.py @@ -1,8 +1,9 @@ -import os +from os import path, system import math import json import time from datetime import datetime + import threading import RPi.GPIO as GPIO import logging @@ -12,40 +13,33 @@ from SensorReaderService import SensorReaderService # from PWMController import PWMController from MQTTTransceiver import MQTTTransceiver +from PID import PID # Internal parameters T_IN = 2 # inspiratory time T_EX = 3 # expiratory time T_WT = 1 # waiting time -Pi = 2000 # peak inspiratory pressure in cmH2O PWM_FREQ = 2 # frequency for PWM +pid = None # Constants SI_PIN = 12 # PIN (PWM) for inspiratory solenoid -SO_PIN = 13 # PIN 6 used for medical air valve +SO_PIN = 13 # PIN 6 used for medical air valve SE_PIN = 6 # PIN (PWM) for expiratory solenoid INSP_FLOW = True EXP_FLOW = False DUTY_RATIO_100 = 100 DUTY_RATIO_0 = 0 -DISPLAY_TIME_AXIS = 0 # time axis value in display -DISPLAY_TIME_RANGE = 20 # the range of time axis in display -INSP_TOTAL_VOLUME = 0 # total inspiratory volume delivered - -# No longer need. Controller now uses SensorReaderService -# NUMBER_OF_SENSORS = 4 -# BUS_1 = Variables.BUS_1 -# BUS_2 = Variables.BUS_2 -# BUS_3 = Variables.BUS_3 -# BUS_4 = Variables.BUS_4 -# INSP_PHASE = "inspiratory" -# EXP_PHASE = "expiratory" -# threads_map = {} - -pressure_data = [0] * 6 +INSP_TOTAL_VOLUME = 0 # total inspiratory volume delivered PWM_I, PWM_O = None, None +# Last pressure data +last_p1 = 0; +last_p2 = 0; +last_p3 = 0; +last_p4 = 0; + mqtt = None sensing_service = None Ki, Ke = 0, 0 @@ -56,51 +50,6 @@ logging.config.fileConfig(fname='logger.conf', disable_existing_loggers=False) logger = logging.getLogger(__name__) -# No longer need. Controller now uses SensorReaderService -# def thread_slice(pressure_data, index): -# sr = SensorReader(index) -# pressure = sr.read_pressure() -# pressure_data[index] = pressure - - -# No longer need. Controller now uses SensorReaderService -# def read_data(phase=""): -# # read relevant pressure sensors from the smbus and return actual values -# threads = list() -# if phase == INSP_PHASE: -# for index in [BUS_1, BUS_2, BUS_3]: -# thread = threading.Thread( -# target=thread_slice, args=(pressure_data, index,)) -# threads.append(thread) -# thread.start() -# for index, thread in enumerate(threads): -# thread.join() -# logger.debug("Pressure: P1[%.2f], P2[%.2f], P3[%.2f]" % -# (pressure_data[BUS_1], pressure_data[BUS_2], pressure_data[BUS_3])) -# return pressure_data[BUS_1], pressure_data[BUS_2], pressure_data[BUS_3] -# elif phase == EXP_PHASE: -# for index in [BUS_3, BUS_4]: -# thread = threading.Thread( -# target=thread_slice, args=(pressure_data, index,)) -# threads.append(thread) -# thread.start() -# for index, thread in enumerate(threads): -# thread.join() -# logger.debug("Pressure: P3[%.2f], P4[%.2f]" % -# (pressure_data[BUS_3], pressure_data[BUS_4])) -# return pressure_data[BUS_3], pressure_data[BUS_4] -# else: -# for index in [BUS_1, BUS_2, BUS_3, BUS_4]: -# thread = threading.Thread( -# target=thread_slice, args=(pressure_data, index,)) -# threads.append(thread) -# thread.start() -# for index, thread in enumerate(threads): -# thread.join() -# logger.debug("Pressure: P1[%.2f], P2[%.2f], P3[%.2f], P4[%.2f]" % -# (pressure_data[BUS_1], pressure_data[BUS_2], pressure_data[BUS_3], pressure_data[BUS_4])) -# return pressure_data[BUS_1], pressure_data[BUS_2], pressure_data[BUS_3], pressure_data[BUS_4] - def calculate_k(p1, p2, flow_rate): return flow_rate / math.sqrt(abs(p1 - p2)) @@ -125,7 +74,6 @@ def calibrate_flow_meter(flow_rate): ke = 0 # Take the average over 'nSamples' pressure readings, 'delay' seconds apart to calculate k while n < nSamples: - # p1, p2, p3, p4 = read_data() ki += calculate_k(Variables.p1, Variables.p2, flow_rate) ke += calculate_k(Variables.p3, Variables.p4, flow_rate) n += 1 @@ -154,27 +102,6 @@ def control_solenoid(pin, duty_ratio): GPIO.output(SE_PIN, level) -# No longer in use. This is to emulate PWM on digital pins -# def control_solenoid(pin, duty_ratio): -# """ emulate pwm on a digital out pin """ -# logger.info("Entering control_solenoid()...") -# on_time = PWM_PERIOD * duty_ratio -# off_time = PWM_PERIOD * (1 - duty_ratio) -# -# if pin in threads_map: -# threads_map[pin].stop() -# threads_map[pin].join() -# -# t = PWMController(datetime.now().strftime('%Y%m%d%H%M%S%f'), pin, on_time, off_time) -# threads_map[pin] = t -# -# # Don't want these threads to run when the main program is terminated -# t.daemon = True -# t.start() -# -# logger.info("Leaving control_solenoid().") - - def get_average_flow_rate_and_pressure(is_insp_phase): """ read p1 and p2 over 200 milliseconds and return average volume rate """ @@ -185,10 +112,8 @@ def get_average_flow_rate_and_pressure(is_insp_phase): # Take the average over 'nSamples' pressure readings, 'delay' seconds apart to calculate flow rate while n < nSamples: if is_insp_phase: - # p1, p2, p3 = read_data(INSP_PHASE) # pressures q += Ki * math.sqrt(abs(Variables.p1 - Variables.p2)) # flow rate else: - # p3, p4 = read_data(EXP_PHASE) # pressures q += Ke * math.sqrt(abs(Variables.p3 - Variables.p4)) # flow rate p += Variables.p3 @@ -199,13 +124,16 @@ def get_average_flow_rate_and_pressure(is_insp_phase): return q / nSamples, p / nSamples -def calculate_pid_duty_ratio(demo_level): - """ TODO: implement the PID controller to determine the required duty ratio to achieve the desired pressure curve - Currently a temporary hack is implemented with demo_level """ - duty_ratio = 100 - if demo_level == 1: - duty_ratio = 20 +def calculate_pid_duty_ratio(pressure): + """ PID controller determines the required duty ratio to achieve the desired pressure curve """ + logger.debug("<<<< HIT PID Controller >>>> : pressure = " + str(convert_pressure(pressure))) + pid.update(convert_pressure(pressure)) + duty_ratio = pid.output + # Duty ratio is adjusted between 0 and 100 + duty_ratio = max(min(int(duty_ratio), 100), 0) + + logger.debug("<<<< LEAVE PID Controller >>>> : duty_ratio = " + str(duty_ratio)) return duty_ratio @@ -222,29 +150,26 @@ def create_chart_payload(t, pressure, flow_rate, volume): def send_to_display(timeT, pressure, flow_rate, volume): """ send the given parameters to display unit via mqtt """ - # mqtt.sender(mqtt.PRESSURE_TOPIC, convert_pressure(pressure)) - # mqtt.sender(mqtt.FLOWRATE_TOPIC, flow_rate) - # mqtt.sender(mqtt.VOLUME_TOPIC, volume) - payload = create_chart_payload(timeT, convert_pressure(pressure), flow_rate, volume) mqtt.sender(mqtt.CHART_DATA_TOPIC, payload) logger.debug(payload) -def insp_phase(demo_level): - """ inspiratory phase tasks - demo_level is a temporary hack to introduce two flow rate levels until pid controller is implemented """ +def insp_phase(): + """ inspiratory phase tasks """ - global INSP_TOTAL_VOLUME + global INSP_TOTAL_VOLUME, TIME_REF_MINUTE_VOL logger.info("Entering inspiratory phase...") + # beep sound added to inspiratory cycle - os.system("echo -ne '\007'") + system("echo -ne '\007'") + start_time = datetime.now() t1, t2 = start_time, start_time ti = 0 # instantaneous time q1, q2 = 0, 0 # flow rates vi = 0 # volume - pip = 0 # peak inspiratory pressure + pip = 0 # peak inspiratory pressure solenoids_closed = False # Control solenoids @@ -252,8 +177,13 @@ def insp_phase(demo_level): control_solenoid(SO_PIN, DUTY_RATIO_100) control_solenoid(SE_PIN, DUTY_RATIO_0) + # Reset inspiratory cycle volume + INSP_TOTAL_VOLUME = 0 + while ti < T_IN: + send_pressure_data() + t1 = t2 q1 = q2 q2, p3 = get_average_flow_rate_and_pressure(INSP_FLOW) @@ -272,7 +202,6 @@ def insp_phase(demo_level): solenoids_closed = True ti = (t2 - start_time).total_seconds() - delta_t = (t2 - t1).total_seconds() send_to_display(t2, p3, 0, vi) # flow rate is 0 when insp. solenoid is closed continue @@ -280,23 +209,21 @@ def insp_phase(demo_level): vi += 1000 * (q1 + q2) / 2 * (t2 - t1).total_seconds() / 60 # TODO: separately calculate di for inp and oxy solenoids. - di = calculate_pid_duty_ratio(demo_level) + di = calculate_pid_duty_ratio(p3) control_solenoid(SI_PIN, di) control_solenoid(SO_PIN, di) ti = (t2 - start_time).total_seconds() - delta_t = (t2 - t1).total_seconds() send_to_display(t2, p3, q2, vi) - logger.debug("fio2: %.2f, vt: %.2f, ie: %.2f, rr: %.2f, peep: %.2f" % ( - Variables.fio2, Variables.vt, Variables.ie, Variables.rr, Variables.peep)) + logger.debug("Psupport: %.1f, Pcurrent: %.1f, Duty_Ratio: %.2f" % (Variables.ps, convert_pressure(p3), di)) # Store tidal volume for expiratory phase net volume calculation INSP_TOTAL_VOLUME = vi # Send pip to GUI - mqtt.sender(mqtt.PIP_TOPIC, pip) - logger.info("[%.4f] Pip is : %.3f mL " % (ti, pip)) + mqtt.sender(mqtt.PIP_TOPIC, round(convert_pressure(pip), 1)) + logger.info("[%.4f] Pip is : %.3f mL " % (ti, convert_pressure(pip))) logger.info("Leaving inspiratory phase.") @@ -310,7 +237,7 @@ def exp_phase(): t1, t2 = start_time, start_time ti = 0 q1, q2 = 0, 0 - vi = 0 + vi, v_tot = 0, 0 control_solenoid(SI_PIN, DUTY_RATIO_0) control_solenoid(SO_PIN, DUTY_RATIO_0) @@ -321,36 +248,74 @@ def exp_phase(): TIME_REF_MINUTE_VOL = start_time while ti < T_EX: + + send_pressure_data() + t1 = t2 q1 = q2 q2, p3 = get_average_flow_rate_and_pressure(EXP_FLOW) t2 = datetime.now() # Calculate volume - vi += 1000 * (q1 + q2) / 2 * (t2 - t1).total_seconds() / 60 + vi = 1000 * (q1 + q2) / 2 * (t2 - t1).total_seconds() / 60 + v_tot += vi ti = (t2 - start_time).total_seconds() + # Handle minute volume calculations if (t2 - TIME_REF_MINUTE_VOL).total_seconds() < 60: + logger.debug("<<< EXP >> vi=%.1f min_vol=%.1f", (vi, MINUTE_VOLUME)) MINUTE_VOLUME += vi else: - # Send minute volume to GUI - mqtt.sender(mqtt.MINUTE_VOLUME_TOPIC, round(MINUTE_VOLUME, 2)) - logger.info("[%.4f] Minute volume is : %.2f mL " % (ti, MINUTE_VOLUME)) + logger.debug("<<< EXP - RESET >> vi=%.1f min_vol=%.1f", (vi, MINUTE_VOLUME)) + submit_minute_vol(t2) - # Reset minute volume calculation - TIME_REF_MINUTE_VOL = t2 - MINUTE_VOLUME = 0 + send_to_display(t2, p3, (-1 * q2), (INSP_TOTAL_VOLUME - v_tot)) + logger.debug("ti = %.4f, vi = %.1f" % (ti, vi)) - delta_t = (t2 - t1).total_seconds() - send_to_display(t2, p3, (-1 * q2), (INSP_TOTAL_VOLUME - vi)) - logger.debug("ti = %.4f, T_EX = %.4f" % (ti, T_EX)) - - logger.info("<< CHART >> Actual tidal volume delivered : %.3f mL " % vi) - mqtt.sender(mqtt.ACTUAL_TIDAL_VOLUME_TOPIC, vi) + logger.info("<< CHART >> Actual tidal volume delivered : %.3f mL " % v_tot) + mqtt.sender(mqtt.ACTUAL_TIDAL_VOLUME_TOPIC, round(v_tot)) INSP_TOTAL_VOLUME = 0 logger.info("Leaving expiratory phase.") +def send_pressure_data(): + """ send the pressure parameters to display unit via mqtt """ + + global last_p1, last_p2, last_p3, last_p4 + + p1 = convert_pressure(Variables.p1) + p2 = convert_pressure(Variables.p2) + p3 = convert_pressure(Variables.p3) + p4 = convert_pressure(Variables.p4) + + payload = { + 'delta_p1': p1-last_p1, + 'delta_p2': p2-last_p2, + 'delta_p3': p3-last_p3, + 'delta_p4': p4-last_p4 + } + mqtt.sender(mqtt.PRESSURE_DATA_TOPIC, payload) + + last_p1 = p1 + last_p2 = p2 + last_p3 = p3 + last_p4 = p4 + + logger.debug(payload) + + +def submit_minute_vol(reset_time): + global TIME_REF_MINUTE_VOL, MINUTE_VOLUME + + # Send minute volume to GUI + mqtt.sender(mqtt.MINUTE_VOLUME_TOPIC, round(MINUTE_VOLUME)) + logger.debug("<<< SUBMIT >> min_vol=%.1f", MINUTE_VOLUME) + + # Reset minute volume calculation + TIME_REF_MINUTE_VOL = reset_time + MINUTE_VOLUME = 0 + + def wait_phase(): """ waiting phase tasks """ logger.info("Entering wait phase...") @@ -376,7 +341,7 @@ def calc_respiratory_params(): # Initialize the parameters def init_parameters(): - global PWM_I, PWM_O, sensing_service, mqtt + global PWM_I, PWM_O, sensing_service, mqtt, pid # Initialize PWM pins GPIO.setmode(GPIO.BCM) @@ -396,6 +361,11 @@ def init_parameters(): # Start the MQTT transceiver to communicate with GUI mqtt = MQTTTransceiver() + # Initialize PID Controller + pid = PID(Variables.Kp, Variables.Ki, Variables.Kd) + pid.SetPoint = Variables.ps + pid.setSampleTime(Variables.pid_sampling_period) + calc_respiratory_params() @@ -412,19 +382,9 @@ def init_parameters(): Ki, Ke = calibrate_flow_meter(Variables.calib_flow_rate) while True: - # slow flow rate - # logger.info("***** Slower flow rate cycle *****") - # insp_phase(1) - # exp_phase() - # wait_phase() - # logger.info("***** Slower cycle end *****") - - # faster flow rate - logger.info("***** Faster flow rate cycle *****") - insp_phase(2) + insp_phase() exp_phase() # wait_phase() - logger.info("***** Faster cycle end *****") # use the latest input parameters set via UI calc_respiratory_params() diff --git a/Firmware/RaspberryPi/backend-pi/MQTTTransceiver.py b/Firmware/RaspberryPi/backend-pi/MQTTTransceiver.py index 8942c03..3c9a98c 100644 --- a/Firmware/RaspberryPi/backend-pi/MQTTTransceiver.py +++ b/Firmware/RaspberryPi/backend-pi/MQTTTransceiver.py @@ -9,13 +9,11 @@ class MQTTTransceiver: - PRESSURE_TOPIC = 'Ventilator/pressure' - FLOWRATE_TOPIC = 'Ventilator/flow_rate' - VOLUME_TOPIC = 'Ventilator/volume' CHART_DATA_TOPIC = 'Ventilator/chart_data' ACTUAL_TIDAL_VOLUME_TOPIC = 'Ventilator/vt' MINUTE_VOLUME_TOPIC = 'Ventilator/minute_volume' PIP_TOPIC = 'Ventilator/pip' + PRESSURE_DATA_TOPIC = "Ventilator/pressure_data" CALIB_FLOW_RATE_CONFIG_TOPIC = 'Config/calib_flow_rate' FIO2_CONFIG_TOPIC = 'Config/fio2' diff --git a/Firmware/RaspberryPi/backend-pi/PID.py b/Firmware/RaspberryPi/backend-pi/PID.py new file mode 100644 index 0000000..b335f9c --- /dev/null +++ b/Firmware/RaspberryPi/backend-pi/PID.py @@ -0,0 +1,129 @@ +#!/usr/bin/python +# +# This file is part of IvPID. +# Copyright (C) 2015 Ivmech Mechatronics Ltd. +# +# IvPID is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# IvPID is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +# title :PID.py +# description :python pid controller +# author :Caner Durmusoglu +# date :20151218 +# version :0.1 +# notes : +# python_version :2.7 +# ============================================================================== + +"""Ivmech PID Controller is simple implementation of a Proportional-Integral-Derivative (PID) Controller in the Python Programming Language. +More information about PID Controller: http://en.wikipedia.org/wiki/PID_controller +""" +import time + +class PID: + """PID Controller + """ + + def __init__(self, P=0.2, I=0.0, D=0.0, current_time=None): + + self.Kp = P + self.Ki = I + self.Kd = D + + self.sample_time = 0.00 + self.current_time = current_time if current_time is not None else time.time() + self.last_time = self.current_time + + self.clear() + + def clear(self): + """Clears PID computations and coefficients""" + self.SetPoint = 0.0 + + self.PTerm = 0.0 + self.ITerm = 0.0 + self.DTerm = 0.0 + self.last_error = 0.0 + + # Windup Guard + self.int_error = 0.0 + self.windup_guard = 20.0 + + self.output = 0.0 + + def update(self, feedback_value, current_time=None): + """Calculates PID value for given reference feedback + + .. math:: + u(t) = K_p e(t) + K_i \int_{0}^{t} e(t)dt + K_d {de}/{dt} + + .. figure:: images/pid_1.png + :align: center + + Test PID with Kp=1.2, Ki=1, Kd=0.001 (test_pid.py) + + """ + error = self.SetPoint - feedback_value + + self.current_time = current_time if current_time is not None else time.time() + delta_time = self.current_time - self.last_time + delta_error = error - self.last_error + + if (delta_time >= self.sample_time): + self.PTerm = self.Kp * error + self.ITerm += error * delta_time + + if (self.ITerm < -self.windup_guard): + self.ITerm = -self.windup_guard + elif (self.ITerm > self.windup_guard): + self.ITerm = self.windup_guard + + self.DTerm = 0.0 + if delta_time > 0: + self.DTerm = delta_error / delta_time + + # Remember last time and last error for next calculation + self.last_time = self.current_time + self.last_error = error + + self.output = self.PTerm + (self.Ki * self.ITerm) + (self.Kd * self.DTerm) + + def setKp(self, proportional_gain): + """Determines how aggressively the PID reacts to the current error with setting Proportional Gain""" + self.Kp = proportional_gain + + def setKi(self, integral_gain): + """Determines how aggressively the PID reacts to the current error with setting Integral Gain""" + self.Ki = integral_gain + + def setKd(self, derivative_gain): + """Determines how aggressively the PID reacts to the current error with setting Derivative Gain""" + self.Kd = derivative_gain + + def setWindup(self, windup): + """Integral windup, also known as integrator windup or reset windup, + refers to the situation in a PID feedback controller where + a large change in setpoint occurs (say a positive change) + and the integral terms accumulates a significant error + during the rise (windup), thus overshooting and continuing + to increase as this accumulated error is unwound + (offset by errors in the other direction). + The specific problem is the excess overshooting. + """ + self.windup_guard = windup + + def setSampleTime(self, sample_time): + """PID that should be updated at a regular interval. + Based on a pre-determined sampe time, the PID decides if it should compute or return immediately. + """ + self.sample_time = sample_time \ No newline at end of file diff --git a/Firmware/RaspberryPi/backend-pi/RnD/PIDControllerTuner.py b/Firmware/RaspberryPi/backend-pi/RnD/PIDControllerTuner.py new file mode 100644 index 0000000..9a8b0fa --- /dev/null +++ b/Firmware/RaspberryPi/backend-pi/RnD/PIDControllerTuner.py @@ -0,0 +1,95 @@ +import sys +sys.path.append('..') + +from PID import PID +from SensorReaderService import SensorReaderService +from Variables import Variables +import time +from os import path +import RPi.GPIO as GPIO + +# Constants +PWM_FREQ = 2 # frequency for PWM +SO_PIN = 6 # PIN (PWM) for O2 intake solenoid +SI_PIN = 12 # PIN (PWM) for inspiratory solenoid +SE_PIN = 14 # PIN (PWM) for expiratory solenoid +PWM_O = None +PWM_I = None +PWM_E = None +pid = None + + +def load_pid_config(): + global pid + with open('./pid.conf', 'r') as f: + config = f.readline().split(',') + pid.SetPoint = float(Variables.ps) + pid.setKp(float(config[0])) + pid.setKi(float(config[1])) + pid.setKd(float(config[2])) + + +def create_pid_config(): + if not path.isfile('./pid.conf'): + with open('./pid.conf', 'w') as f: + f.write('%s,%s,%s' % (Variables.Kp, Variables.Ki, Variables.Kd)) + + +def convert_pressure(p_hpa): + """ returns inspiratory pressure relative to atm in cmH2O""" + return (p_hpa * 1.0197442) - 1033.23 + + +def init_parameters(): + global PWM_O, PWM_I, PWM_E, pid + + # Initialize PWM pins + GPIO.setmode(GPIO.BCM) + GPIO.setwarnings(False) + GPIO.setup(SO_PIN, GPIO.OUT) + GPIO.setup(SI_PIN, GPIO.OUT) + GPIO.setup(SE_PIN, GPIO.OUT) + + PWM_O = GPIO.PWM(SO_PIN, PWM_FREQ) + PWM_I = GPIO.PWM(SI_PIN, PWM_FREQ) + PWM_E = GPIO.PWM(SE_PIN, PWM_FREQ) + + # Start the sensor reading service + sensing_service = SensorReaderService() + + # Initialize PID controller + create_pid_config() + pid = PID(Variables.Kp, Variables.Ki, Variables.Kd) + pid.SetPoint = Variables.ps + pid.setSampleTime(Variables.pid_sampling_period) + + # Open all values + PWM_O.ChangeDutyCycle(100) + PWM_I.ChangeDutyCycle(100) + PWM_E.ChangeDutyCycle(0) # Normally open, hence duty_ratio=0 + +################################################################### + + +init_parameters() + +while True: + # load the latest PID related config. [Kp, Ki, Kd] + load_pid_config() + + # read pressure data + pressure = Variables.p3 + + if pressure is None: + continue + + pid.update(convert_pressure(pressure)) + target_duty_ratio = pid.output + target_duty_ratio = max(min(int(target_duty_ratio), 100), 0) + + print("Target: %.1f | Current: %.1f | Duty Ratio: %d" % (Variables.ps, convert_pressure(pressure), target_duty_ratio)) + + # Set PWM to target duty + PWM_I.ChangeDutyCycle(target_duty_ratio) + + time.sleep(Variables.pid_sampling_period - 0.005) diff --git a/Firmware/RaspberryPi/backend-pi/RnD/pid.conf b/Firmware/RaspberryPi/backend-pi/RnD/pid.conf new file mode 100644 index 0000000..bb90ffc --- /dev/null +++ b/Firmware/RaspberryPi/backend-pi/RnD/pid.conf @@ -0,0 +1 @@ +10,1,1 \ No newline at end of file diff --git a/Firmware/RaspberryPi/backend-pi/SensorReader.py b/Firmware/RaspberryPi/backend-pi/SensorReader.py index 1f2513c..ab1be31 100644 --- a/Firmware/RaspberryPi/backend-pi/SensorReader.py +++ b/Firmware/RaspberryPi/backend-pi/SensorReader.py @@ -2,7 +2,6 @@ import time import bme680 from Variables import Variables -from datetime import datetime class SensorReader: @@ -64,7 +63,9 @@ def read_temp(self): self.fTemp = self.cTemp * 1.8 + 32 def read_pressure(self): - if (self.bus_number == Variables.BUS_3): + + # For demo p3 is read from a bme680 sensor + if Variables.demo and self.bus_number == Variables.BUS_3: return self.read_bme680() #Reading Data from i2c bus 3 diff --git a/Firmware/RaspberryPi/backend-pi/Variables.py b/Firmware/RaspberryPi/backend-pi/Variables.py index 971f1f8..32d1496 100644 --- a/Firmware/RaspberryPi/backend-pi/Variables.py +++ b/Firmware/RaspberryPi/backend-pi/Variables.py @@ -5,18 +5,32 @@ class Variables: + # Pressure sensor BUS ids BUS_1 = 1 # first inspiratory pressure sensor BUS_2 = 3 # second inspiratory pressure sensor BUS_3 = 4 # first expiratory pressure sensor BUS_4 = 5 # second expiratory pressure sensor - calib_flow_rate = 10 # flow rate for calibration + + # Pressure sensor values + p1 = 0 # pressure sensor 1 on inspiratory phase + p2 = 0 # pressure sensor 2 on inspiratory phase + p3 = 0 # pressure sensor 3 on expiratory phase + p4 = 0 # pressure sensor 4 on expiratory phase + + # From GUI + calib_flow_rate = -1 # flow rate used for calibration. Set by GUI fio2 = 0 # fio2 value ie = 1 # I:E ratio rr = 10 # respiratory rate (RR) vt = 500 # tidal volume (mL) peep = 10 # PEEP ps = 20 # pressure support (Ps) - p1 = 0 # pressure sensor 1 on inspiratory phase - p2 = 0 # pressure sensor 2 on inspiratory phase - p3 = 0 # pressure sensor 3 on expiratory phase - p4 = 0 # pressure sensor 4 on expiratory phase + + # PID controller parameters + Kp = 10 + Ki = 1 + Kd = 1 + pid_sampling_period = 0.2 + + # Flag to indicate demo setup, where P3 is from a BME680 sensor + demo = False diff --git a/Firmware/RaspberryPi/frontend-pi/public/index.html b/Firmware/RaspberryPi/frontend-pi/public/index.html index 87c7b97..a81d73a 100644 --- a/Firmware/RaspberryPi/frontend-pi/public/index.html +++ b/Firmware/RaspberryPi/frontend-pi/public/index.html @@ -130,13 +130,13 @@