├── .github ├── dependabot.yml └── workflows │ └── build.yml ├── .gitignore ├── .gitmodules ├── .readthedocs.yml ├── CHANGELOG.md ├── CoffeeMachine ├── CoffeeMachine.ino └── libraries │ ├── SSD1306_ascii_display.h │ ├── arduino_adapter.h │ ├── arduino_pid.h │ ├── arduino_pin.h │ ├── arduino_serial.h │ ├── configuration.h │ ├── factories.h │ ├── ktype_thermocouple.h │ └── tsic_sensor.h ├── LICENSE ├── Makefile ├── README.md ├── docker ├── Dockerfile └── docker-compose.yml ├── docs ├── Makefile ├── conf.py ├── index.rst ├── make.bat ├── misc │ └── GaggiaPIDController.fzz ├── requirements.txt └── src │ ├── documentation.rst │ ├── images │ ├── GaggiaPIDController_bb.jpg │ ├── arduino_and_ssr.jpg │ ├── arduino_nano.jpg │ ├── clamp_wire_connecttors.jpg │ ├── final_mod.jpg │ ├── final_mod_inside.jpg │ ├── ktype_thermocouple.jpg │ ├── max6675_module.jpg │ ├── pid_tuning_screenshot.png │ ├── power_supply.jpg │ ├── ssr_connector.jpg │ ├── temp_sensor_assembled.jpg │ ├── testbench01.jpg │ └── ttap_connector.jpg │ └── schematics │ └── gaggia_paros_wiring.png ├── scripts └── build-project.sh └── tools ├── .flake8 ├── poetry.lock ├── pyproject.toml └── temp_plotter.py /.github/dependabot.yml: -------------------------------------------------------------------------------- 1 | version: 2 2 | updates: 3 | 4 | # Maintain dependencies for GitHub Actions 5 | - package-ecosystem: "github-actions" 6 | directory: "/" 7 | schedule: 8 | interval: "daily" 9 | -------------------------------------------------------------------------------- /.github/workflows/build.yml: -------------------------------------------------------------------------------- 1 | name: CI pipeline 2 | 3 | on: 4 | push: 5 | pull_request: 6 | branches: 7 | - master 8 | 9 | jobs: 10 | build: 11 | runs-on: ubuntu-latest 12 | name: Build 13 | 14 | steps: 15 | - name: Checkout 16 | uses: actions/checkout@v4 17 | with: 18 | submodules: true 19 | 20 | 21 | - name: Build 22 | run: make ci 23 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | .DS_Store 2 | bin/*/ 3 | *~ 4 | build-tmp/ 5 | doc/ 6 | debug.txt 7 | .ycm_extra_conf.pyc 8 | .ropeproject 9 | .vscode 10 | *.hex 11 | *.elf 12 | build/ 13 | _build/ 14 | 15 | *.egg-info -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "CoffeeMachine/libraries/lib_coffee_machine"] 2 | path = CoffeeMachine/libraries/lib_coffee_machine 3 | url = https://github.com/ilcardella/lib_coffee_machine 4 | -------------------------------------------------------------------------------- /.readthedocs.yml: -------------------------------------------------------------------------------- 1 | # .readthedocs.yml 2 | # Read the Docs configuration file 3 | # See https://docs.readthedocs.io/en/stable/config-file/v2.html for details 4 | 5 | # Required 6 | version: 2 7 | 8 | # Build documentation in the docs/ directory with Sphinx 9 | sphinx: 10 | configuration: docs/conf.py 11 | 12 | # Optionally build your docs in additional formats such as PDF 13 | formats: 14 | - pdf 15 | 16 | build: 17 | image: latest 18 | 19 | # Optionally set the version of Python and requirements required to build your docs 20 | python: 21 | version: 3.8 22 | install: 23 | - requirements: docs/requirements.txt 24 | # - method: pip 25 | # path: . 26 | # extra_requirements: 27 | # - docs 28 | -------------------------------------------------------------------------------- /CHANGELOG.md: -------------------------------------------------------------------------------- 1 | # Arduino Coffee Machine Changelog 2 | 3 | All notable changes to this project will be documented in this file. 4 | 5 | The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/), 6 | and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0.html). 7 | 8 | ## [] 9 | ### Changed 10 | - Updated version of `lib-coffee-machine` and include paths 11 | 12 | ## [2.0.0] - 13/02/2020 13 | ### Added 14 | - Thermocouple sensor support a temperature offset to account for static error 15 | - Wrapper for all Arduino.h functions and types 16 | - CMake configuration for non-Arduino dependant code 17 | - Automated test suite for non-Arduino dependant codebase 18 | - Circuit diagram in documentation 19 | 20 | ### Changed 21 | - Reformat of the `TemperatureSensor` class using template for sensor implementation 22 | - Replaced use of Arduino String with char array 23 | - Configuration for coffee_machine library is provided through a template argument 24 | - Use `lib-coffee-machine` external library for core functionalities 25 | 26 | ### Fixed 27 | - Resolved crash due to String assignments 28 | - Fixed print formatting of float and double 29 | - Fixed bug in MovingAverage affected by the creation of an instance with 0 history length 30 | 31 | ## [1.1.0] - 2020-08-22 32 | ### Added 33 | - Added python script to plot machine temperatures reported through serial interface 34 | - Configurable safety timeouts to turn the heater off after a set period of time 35 | - Added support for K-type thermocouple sensors with MAX6675 and SPI interface 36 | 37 | ### Changed 38 | - Display shows status of the machine indicating if it's heating, cooling or ready for brew 39 | - Performed PID tuning to reduce oscillation of temperature 40 | - Updated steam switch mode to use internal pullup resistor 41 | 42 | ## [1.0.0] - 2020-05-03 43 | ### Added 44 | - First release: 45 | - Support for TSic306 digital temperature sensor 46 | - SSR control with PID loop 47 | - Support for SSD1306 OLED 128x64 display 48 | - Serial interface to show debug information 49 | -------------------------------------------------------------------------------- /CoffeeMachine/CoffeeMachine.ino: -------------------------------------------------------------------------------- 1 | #include "libraries/arduino_adapter.h" 2 | #include "libraries/arduino_pin.h" 3 | #include "libraries/configuration.h" 4 | #include "libraries/factories.h" 5 | 6 | #include "libraries/lib_coffee_machine/include/lib_coffee_machine/coffee_machine.h" 7 | 8 | using Adapter = ArduinoAdapter; 9 | 10 | CoffeeMachine *machine; 11 | 12 | void setup() 13 | { 14 | auto display = DisplayFactory::make_display(); 15 | auto serial = SerialFactory::make_serial_interface(); 16 | auto controller = ControllerFactory::make_controller(); 17 | auto mode_swith_pin = new ArduinoPin(Configuration::STEAM_SWITCH_PIN); 18 | auto heater_pin = new ArduinoPin(Configuration::HEATER_SSR_PIN); 19 | auto water_sensor = SensorFactory::make_water_temperature_sensor(); 20 | auto steam_sensor = SensorFactory::make_steam_temperature_sensor(); 21 | 22 | machine = new CoffeeMachine( 23 | controller, serial, mode_swith_pin, display, heater_pin, water_sensor, 24 | steam_sensor); 25 | 26 | // Allow sensors to initialise 27 | delay(500); 28 | } 29 | 30 | void loop() 31 | { 32 | if (machine) 33 | { 34 | machine->spin(); 35 | delay(1); 36 | } 37 | else 38 | { 39 | Serial.println("Error initialising coffee machine"); 40 | delay(1000); 41 | } 42 | } 43 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/SSD1306_ascii_display.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 4 | 5 | #include 6 | #include 7 | 8 | class SSD1306AsciiDisplay : public BaseDisplay 9 | { 10 | public: 11 | SSD1306AsciiDisplay() 12 | { 13 | } 14 | 15 | bool initialise() override 16 | { 17 | Wire.begin(); 18 | Wire.setClock(400000L); 19 | oled.begin(&Adafruit128x64, 0x3C); 20 | oled.setFont(Adafruit5x7); 21 | clear(); 22 | return true; 23 | } 24 | 25 | bool clear() override 26 | { 27 | oled.clear(); 28 | return true; 29 | } 30 | 31 | bool print(const unsigned &col, const unsigned &row, const char *data) override 32 | { 33 | oled.setCursor(col, row); 34 | oled.print(data); 35 | return true; 36 | } 37 | 38 | bool print(const unsigned &col, const unsigned &row, const int &data) override 39 | { 40 | // TODO 41 | return true; 42 | } 43 | 44 | bool print(const unsigned &col, const unsigned &row, const float &data) override 45 | { 46 | // TODO 47 | return true; 48 | } 49 | 50 | bool print(const unsigned &col, const unsigned &row, const double &data) override 51 | { 52 | // TODO 53 | return true; 54 | } 55 | 56 | bool display() 57 | { 58 | // Nothing to do 59 | return true; 60 | } 61 | 62 | private: 63 | SSD1306AsciiWire oled; 64 | }; 65 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/arduino_adapter.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | 6 | class ArduinoAdapter 7 | { 8 | public: 9 | inline static void pinMode(uint8_t pin, uint8_t mode) 10 | { 11 | ::pinMode(pin, mode); 12 | } 13 | 14 | inline static int digitalRead(uint8_t pin) 15 | { 16 | return ::digitalRead(pin); 17 | } 18 | 19 | inline static void digitalWrite(uint8_t pin, uint8_t val) 20 | { 21 | ::digitalWrite(pin, val); 22 | } 23 | 24 | inline static void delay(unsigned long ms) 25 | { 26 | ::delay(ms); 27 | } 28 | 29 | inline static unsigned long millis() 30 | { 31 | return ::millis(); 32 | } 33 | 34 | inline static void SerialBegin(const unsigned long &baudrate) 35 | { 36 | Serial.begin(baudrate); 37 | } 38 | 39 | inline static int SerialAvailable() 40 | { 41 | return Serial.available(); 42 | } 43 | 44 | inline static void SerialReadStringUntil(const char &terminator, char *data) 45 | { 46 | strcpy(data, Serial.readStringUntil(terminator).c_str()); 47 | } 48 | 49 | inline static size_t SerialPrintln(const char *value) 50 | { 51 | return Serial.println(value); 52 | } 53 | 54 | inline static void WireBegin() 55 | { 56 | Wire.begin(); 57 | } 58 | 59 | inline static void WireSetClock(const uint32_t &clock) 60 | { 61 | Wire.setClock(clock); 62 | } 63 | 64 | inline static char *dtostrf(double val, signed char width, unsigned char prec, 65 | char *s) 66 | 67 | { 68 | return ::dtostrf(val, width, prec, s); 69 | } 70 | }; 71 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/arduino_pid.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 6 | 7 | class ArduinoPID : public Controller 8 | { 9 | public: 10 | ArduinoPID(const double &kp, const double &ki, const double &kd) 11 | : p_gain(kp), i_gain(ki), d_gain(kd), 12 | pid(&pid_input, &pid_output, &pid_setpoint, p_gain, i_gain, d_gain, DIRECT) 13 | { 14 | pid.SetMode(AUTOMATIC); 15 | } 16 | 17 | void set_output_limits(const double &min, const double &max) override 18 | { 19 | pid.SetOutputLimits(min, max); 20 | } 21 | 22 | bool compute(const double &input, const double &setpoint, double &output) override 23 | { 24 | pid_input = input; 25 | pid_setpoint = setpoint; 26 | if (pid.Compute()) 27 | { 28 | output = pid_output; 29 | return true; 30 | } 31 | return false; 32 | } 33 | 34 | bool update_settings(char *raw) override 35 | { 36 | // TODO decode spec and set tunings 37 | pid.SetTunings(0.0, 0.0, 0.0); 38 | } 39 | 40 | private: 41 | PID pid; 42 | double p_gain = 0.0; 43 | double i_gain = 0.0; 44 | double d_gain = 0.0; 45 | double pid_input = 0.0; 46 | double pid_output = 0.0; 47 | double pid_setpoint = 0.0; 48 | }; 49 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/arduino_pin.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 4 | #include 5 | 6 | class ArduinoPin : public IOPin 7 | { 8 | public: 9 | ArduinoPin(const unsigned char &pin) : pin(pin) 10 | { 11 | } 12 | 13 | void set_mode(const IOPin::Modes &mode) 14 | { 15 | uint8_t pin_mode(0); 16 | switch (mode) 17 | { 18 | case IOPin::Modes::IN_PU: 19 | pin_mode = INPUT_PULLUP; 20 | break; 21 | default: 22 | break; 23 | } 24 | pinMode(pin, pin_mode); 25 | } 26 | 27 | bool is_high() override 28 | { 29 | return digitalRead(pin) == HIGH; 30 | } 31 | 32 | bool is_low() override 33 | { 34 | return not is_high(); 35 | } 36 | 37 | void digital_write_high() override 38 | { 39 | digitalWrite(pin, HIGH); 40 | } 41 | 42 | void digital_write_low() override 43 | { 44 | digitalWrite(pin, LOW); 45 | } 46 | 47 | private: 48 | unsigned char pin; 49 | }; 50 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/arduino_serial.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 4 | #include 5 | 6 | class ArduinoSerial : public BaseSerialInterface 7 | { 8 | public: 9 | ArduinoSerial() = default; 10 | 11 | void begin(const unsigned long &baudrate) override 12 | { 13 | Serial.begin(baudrate); 14 | } 15 | 16 | int available() override 17 | { 18 | return Serial.available(); 19 | } 20 | 21 | void read_string_until(const char &terminator, char *data) override 22 | { 23 | strcpy(data, Serial.readStringUntil(terminator).c_str()); 24 | } 25 | 26 | size_t println(const char *value) override 27 | { 28 | Serial.println(value); 29 | } 30 | }; 31 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/configuration.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "lib_coffee_machine/include/lib_coffee_machine/default/configuration.h" 4 | 5 | struct Configuration : public DefaultConfiguration 6 | { 7 | enum class SensorTypes 8 | { 9 | TSIC, // TSic sensor family 10 | KTYPE_SPI // K-type thermocouple with SPI interface 11 | }; 12 | 13 | enum class DisplayTypes 14 | { 15 | SSD1306_128x64 16 | }; 17 | 18 | enum class SerialTypes 19 | { 20 | ARDUINO_SERIAL 21 | }; 22 | 23 | enum class TempControllerTypes 24 | { 25 | ARDUINO_PID 26 | }; 27 | 28 | inline static constexpr SensorTypes WATER_TEMP_SENSOR_TYPE = SensorTypes::KTYPE_SPI; 29 | inline static constexpr SensorTypes STEAM_TEMP_SENSOR_TYPE = SensorTypes::KTYPE_SPI; 30 | 31 | inline static constexpr DisplayTypes DISPLAY_TYPE = DisplayTypes::SSD1306_128x64; 32 | 33 | inline static constexpr SerialTypes SERIAL_INTERFACE_TYPE = 34 | SerialTypes::ARDUINO_SERIAL; 35 | 36 | inline static constexpr TempControllerTypes TEMP_CONTROLLER_TYPE = 37 | TempControllerTypes::ARDUINO_PID; 38 | 39 | // Input pin of the water temperature sensor 40 | inline static constexpr unsigned char WATER_TEMP_PIN = 4; 41 | // Input pin of the steam temperature sensor 42 | inline static constexpr unsigned char STEAM_TEMP_PIN = 5; 43 | 44 | // Output PWM pin to control the boiler 45 | inline static constexpr unsigned char HEATER_SSR_PIN = 6; 46 | 47 | // Input pin to detect steam mode 48 | inline static constexpr unsigned char STEAM_SWITCH_PIN = 7; 49 | 50 | // SPI interface common pins 51 | inline static constexpr unsigned char SPI_CLK_PIN = 8; 52 | inline static constexpr unsigned char SPI_CS_PIN = 9; 53 | }; 54 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/factories.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "SSD1306_ascii_display.h" 4 | #include "arduino_pid.h" 5 | #include "arduino_serial.h" 6 | #include "ktype_thermocouple.h" 7 | #include "tsic_sensor.h" 8 | 9 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 10 | 11 | class SensorFactory 12 | { 13 | public: 14 | template static BaseSensor *make_water_temperature_sensor() 15 | { 16 | return make_temperature_sensor( 17 | Configuration::WATER_TEMP_SENSOR_TYPE, Configuration::WATER_TEMP_PIN); 18 | } 19 | 20 | template static BaseSensor *make_steam_temperature_sensor() 21 | { 22 | return make_temperature_sensor( 23 | Configuration::STEAM_TEMP_SENSOR_TYPE, Configuration::STEAM_TEMP_PIN); 24 | } 25 | 26 | private: 27 | template 28 | static BaseSensor *make_temperature_sensor(typename Configuration::SensorTypes type, 29 | const unsigned char &pin) 30 | { 31 | switch (type) 32 | { 33 | case Configuration::SensorTypes::TSIC: 34 | return new TSICTempSensor(pin); 35 | break; 36 | case Configuration::SensorTypes::KTYPE_SPI: 37 | return new KTypeThermocouple(pin, Configuration::SPI_CLK_PIN, 38 | Configuration::SPI_CS_PIN); 39 | break; 40 | default: 41 | // Ideally we would raise an exception here 42 | return nullptr; 43 | break; 44 | } 45 | } 46 | }; 47 | 48 | class DisplayFactory 49 | { 50 | public: 51 | template static BaseDisplay *make_display() 52 | { 53 | switch (Configuration::DISPLAY_TYPE) 54 | { 55 | case Configuration::DisplayTypes::SSD1306_128x64: 56 | return new SSD1306AsciiDisplay(); 57 | break; 58 | default: 59 | // Ideally we would raise an exception here 60 | return nullptr; 61 | break; 62 | } 63 | } 64 | }; 65 | 66 | class ControllerFactory 67 | { 68 | public: 69 | template static Controller *make_controller() 70 | { 71 | switch (Configuration::TEMP_CONTROLLER_TYPE) 72 | { 73 | case Configuration::TempControllerTypes::ARDUINO_PID: 74 | return new ArduinoPID(Configuration::P_GAIN, Configuration::I_GAIN, 75 | Configuration::D_GAIN); 76 | break; 77 | default: 78 | // Ideally we would raise an exception here 79 | return nullptr; 80 | break; 81 | } 82 | } 83 | }; 84 | 85 | class SerialFactory 86 | { 87 | public: 88 | template static BaseSerialInterface *make_serial_interface() 89 | { 90 | switch (Configuration::SERIAL_INTERFACE_TYPE) 91 | { 92 | case Configuration::SerialTypes::ARDUINO_SERIAL: 93 | return new ArduinoSerial(); 94 | break; 95 | default: 96 | // Ideally we would raise an exception here 97 | return nullptr; 98 | break; 99 | } 100 | } 101 | }; 102 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/ktype_thermocouple.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 4 | 5 | #include 6 | 7 | class KTypeThermocouple : public BaseSensor 8 | { 9 | public: 10 | KTypeThermocouple(const unsigned char &sensor_pin, const unsigned char &clk_pin, 11 | const unsigned char &do_pin) 12 | : sensor(clk_pin, sensor_pin, do_pin) 13 | { 14 | } 15 | 16 | bool read_sensor(float *value) override 17 | { 18 | float reading = sensor.readCelsius(); 19 | if (reading == NAN) 20 | { 21 | return false; 22 | } 23 | *value = reading; 24 | return true; 25 | } 26 | 27 | private: 28 | MAX6675 sensor; 29 | }; 30 | -------------------------------------------------------------------------------- /CoffeeMachine/libraries/tsic_sensor.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "lib_coffee_machine/include/lib_coffee_machine/interfaces.h" 4 | 5 | #include 6 | 7 | class TSICTempSensor : public BaseSensor 8 | { 9 | public: 10 | TSICTempSensor(const unsigned char &pin) : sensor(pin, NO_VCC_PIN, TSIC_30x) 11 | { 12 | pinMode(pin, INPUT); 13 | } 14 | 15 | bool read_sensor(float *value) override 16 | { 17 | unsigned short raw; 18 | if (not sensor.getTemperature(&raw)) 19 | { 20 | return false; 21 | } 22 | // FIXME Occasionally the raw value spikes to 60k+ or other times 23 | // it drops to ~ 0. For this project it should be safe to constraint 24 | // the raw reads between safety margins to ignore these errors. 25 | // At 23C ambient temp the raw value is around 730 26 | if (raw < 600 || raw > 900) 27 | { 28 | return false; 29 | } 30 | 31 | auto temp = sensor.calc_Celsius(&raw); 32 | // FIXME: Same type of check as explained above 33 | if (temp < 10 || temp > 200) 34 | { 35 | return false; 36 | } 37 | 38 | *value = temp; 39 | return true; 40 | } 41 | 42 | private: 43 | TSIC sensor; 44 | }; -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2018 Alberto Cardellini 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | 23 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | ifeq ($(origin .RECIPEPREFIX), undefined) 2 | $(error This Make does not support .RECIPEPREFIX. Please use GNU Make 4.0 or later) 3 | endif 4 | .RECIPEPREFIX = > 5 | 6 | CORE ?= avr 7 | BOARD ?= nano 8 | ENV_VARS = CORE=$(CORE) BOARD=$(BOARD) UID=$(shell id -u) GID=$(shell id -g) 9 | DOCKER_COMPOSE = $(ENV_VARS) docker-compose -f docker/docker-compose.yml up 10 | DOCKER_BUILD = $(ENV_VARS) docker-compose -f docker/docker-compose.yml build --force-rm --no-cache 11 | 12 | default: ci 13 | 14 | docker: 15 | > $(DOCKER_BUILD) arduino-builder 16 | > $(DOCKER_BUILD) docs-builder 17 | 18 | build: 19 | > $(DOCKER_COMPOSE) --exit-code-from arduino-builder arduino-builder 20 | 21 | docs: 22 | > $(DOCKER_COMPOSE) --exit-code-from docs-builder docs-builder 23 | 24 | ci: docker build docs 25 | 26 | clean: 27 | > rm -rf build 28 | 29 | .PHONY: default build docs ci docker clean 30 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Arduino Coffee Machine [![Documentation Status](https://readthedocs.org/projects/arduinocoffeemachine/badge/?version=latest)](https://arduinocoffeemachine.readthedocs.io/en/latest/?badge=latest) 2 | 3 | This project is a PID controller for a `Gaggia Paros` (or Gaggia Classic) coffee machine using Arduino and a few other components. 4 | This Arduino based controller improves the stability of the water temperature of the coffee machine by controlling the boiler with a PID control loop feedback. 5 | 6 | ## Software 7 | 8 | This project is based on [lib_coffee_machine](https://github.com/ilcardella/lib_coffee_machine) which is a C++ library providing an abstraction of a generic coffee machine. 9 | 10 | This project implements the library interfaces targeting an Arduino Nano platform and several sensors and displays. 11 | 12 | ### Arduino libraries 13 | 14 | This project depends on the following Arduino libraries: 15 | - [PID](https://github.com/br3ttb/Arduino-PID-Library) 16 | - [TSIC](https://github.com/Schm1tz1/arduino-tsic) 17 | - [SDD1306Ascii](https://github.com/greiman/SSD1306Ascii) 18 | - [MAX6675](https://github.com/adafruit/MAX6675-library) 19 | 20 | ### Makefile 21 | 22 | The `Makefile` at the project root directory provides targets to build the code and the documentation. 23 | 24 | ### Build 25 | 26 | You can build the code with different approaches: 27 | - with the Arduino IDE opening the `CoffeeMachine.ino` sketch 28 | - with VSCode and the [Arduino extension](https://marketplace.visualstudio.com/items?itemName=vsciot-vscode.vscode-arduino) opening the `CoffeeMachine.ino` sketch 29 | - with `make build` using Docker 30 | 31 | #### Build with Docker 32 | 33 | The code can be built inside a Docker container using docker-compose. The `docker-compose.yml` and the `Dockerfile` are in the `docker` directory. The `docker-compose.yml` depends on 2 environment variables that must be defined before starting the build: 34 | - CORE: the Arduino core 35 | - BOARD: the Arduino board to use 36 | 37 | Refer to the [arduino-cli](https://arduino.github.io/arduino-cli/) documentation for the list of available cores and boards. 38 | The following is an example that builds the code for an Arduino Nano board: 39 | 40 | ``` 41 | $ cd /path/to/repo 42 | $ CORE=avr BOARD=nano make build 43 | ``` 44 | 45 | The generated build files will be in the `CoffeeMachine/build` directory. 46 | 47 | After building the Docker image the first time, you can then use the `arduino-cli` installed in the Docker image directly with: 48 | 49 | ``` 50 | $ cd /path/to/repo 51 | $ docker run --rm -it -v $PWD:/build arduino-builder arduino-cli version 52 | arduino-cli Version: 0.10.0 Commit: ec5c3ed 53 | ``` 54 | 55 | ## Hardware 56 | 57 | ### Components 58 | 59 | This is the list of components I used for the project: 60 | - 1x Arduino Nano (any board type will do) 61 | - 1x Solid State Relay 40A 62 | - 2x Digital temperature sensors (e.g. TSic306) 63 | - 1x I2C 128x64 OLED 64 | - Wires and other supplies 65 | 66 | ## Documentation 67 | 68 | Read the project documentation at: https://arduinocoffeemachine.readthedocs.io 69 | 70 | Or build it locally with: 71 | 72 | ``` 73 | $ cd /path/to/repo 74 | $ make docs 75 | ``` 76 | 77 | ## Tools 78 | 79 | The `tools` directory contains a Python script that can be used to read the Arduino 80 | Serial messages and to plot the current water temperature on a graph. The goal 81 | is to help the PID tuning process showing the realtime results. 82 | 83 | ``` 84 | $ cd tools 85 | $ poetry install --no-dev 86 | $ poetry run python temp_plotter.py 87 | ``` 88 | 89 | ## Acknowledgement 90 | 91 | A big thanks goes to these two other projects that helped me a lot in the understanding of the electric schematics of the coffee machine and the components to use: 92 | - [RaspberryPI based](http://int03.co.uk/blog/project-coffee-espiresso-machine/) 93 | - [Arduino based](http://www.cyberelectronics.org/?p=458) 94 | -------------------------------------------------------------------------------- /docker/Dockerfile: -------------------------------------------------------------------------------- 1 | # Image used to build the source code 2 | 3 | FROM ubuntu:latest AS arduino-builder 4 | 5 | ENV DEBIAN_FRONTEND noninteractive 6 | RUN apt-get update \ 7 | && apt-get install -y \ 8 | curl \ 9 | build-essential \ 10 | cmake \ 11 | && rm -rf /var/lib/apt/lists/* 12 | 13 | # Install arduino build tools 14 | ENV BINDIR=/usr/local/bin 15 | RUN mkdir -p /.arduino15 && chmod 777 /.arduino15 \ 16 | && mkdir -p /Arduino && chmod 777 /Arduino \ 17 | && mkdir -p $BINDIR \ 18 | && curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | sh 19 | 20 | WORKDIR /build 21 | 22 | CMD [ "arduino-cli" "version" ] 23 | 24 | ### Image used to build the sphinx documentation 25 | 26 | FROM sphinxdoc/sphinx:latest AS docs-builder 27 | 28 | RUN python3 -m pip install sphinx-rtd-theme 29 | 30 | WORKDIR /build 31 | -------------------------------------------------------------------------------- /docker/docker-compose.yml: -------------------------------------------------------------------------------- 1 | version: '3.7' 2 | services: 3 | arduino-builder: 4 | build: 5 | context: . 6 | target: arduino-builder 7 | image: arduino_coffee_machine/arduino-builder 8 | command: scripts/build-project.sh $CORE $BOARD 9 | user: $UID:$GID 10 | volumes: 11 | - "../:/build" 12 | docs-builder: 13 | build: 14 | context: . 15 | target: docs-builder 16 | image: arduino_coffee_machine/docs-builder 17 | command: make -C docs html 18 | user: $UID:$GID 19 | volumes: 20 | - "../:/build" 21 | -------------------------------------------------------------------------------- /docs/Makefile: -------------------------------------------------------------------------------- 1 | # Minimal makefile for Sphinx documentation 2 | # 3 | 4 | # You can set these variables from the command line, and also 5 | # from the environment for the first two. 6 | SPHINXOPTS ?= 7 | SPHINXBUILD ?= sphinx-build 8 | SOURCEDIR = . 9 | BUILDDIR = _build 10 | 11 | # Put it first so that "make" without argument is like "make help". 12 | help: 13 | @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 14 | 15 | .PHONY: help Makefile 16 | 17 | # Catch-all target: route all unknown targets to Sphinx using the new 18 | # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). 19 | %: Makefile 20 | @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 21 | -------------------------------------------------------------------------------- /docs/conf.py: -------------------------------------------------------------------------------- 1 | # Configuration file for the Sphinx documentation builder. 2 | # 3 | # This file only contains a selection of the most common options. For a full 4 | # list see the documentation: 5 | # https://www.sphinx-doc.org/en/master/usage/configuration.html 6 | 7 | # -- Path setup -------------------------------------------------------------- 8 | 9 | # If extensions (or modules to document with autodoc) are in another directory, 10 | # add these directories to sys.path here. If the directory is relative to the 11 | # documentation root, use os.path.abspath to make it absolute, like shown here. 12 | # 13 | # import os 14 | # import sys 15 | # sys.path.insert(0, os.path.abspath('.')) 16 | 17 | 18 | # -- Project information ----------------------------------------------------- 19 | 20 | project = 'ArduinoCoffee Machine' 21 | copyright = '2020, Alberto Cardellini' 22 | author = 'Alberto Cardellini' 23 | 24 | # The full version, including alpha/beta/rc tags 25 | release = '2.0.0' 26 | 27 | 28 | # -- General configuration --------------------------------------------------- 29 | 30 | master_doc = 'index' 31 | 32 | # Add any Sphinx extension module names here, as strings. They can be 33 | # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom 34 | # ones. 35 | extensions = [ 36 | ] 37 | 38 | # Add any paths that contain templates here, relative to this directory. 39 | templates_path = ['_templates'] 40 | 41 | # List of patterns, relative to source directory, that match files and 42 | # directories to ignore when looking for source files. 43 | # This pattern also affects html_static_path and html_extra_path. 44 | exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] 45 | 46 | 47 | # -- Options for HTML output ------------------------------------------------- 48 | 49 | # The theme to use for HTML and HTML Help pages. See the documentation for 50 | # a list of builtin themes. 51 | # 52 | html_theme = 'sphinx_rtd_theme' 53 | 54 | # Add any paths that contain custom static files (such as style sheets) here, 55 | # relative to this directory. They are copied after the builtin static files, 56 | # so a file named "default.css" will overwrite the builtin "default.css". 57 | html_static_path = ['_static'] 58 | -------------------------------------------------------------------------------- /docs/index.rst: -------------------------------------------------------------------------------- 1 | Arduino Coffee Machine's documentation 2 | ###################################### 3 | 4 | .. important:: This project is a work in progress, I will update the documentation while 5 | I progress with the work and things might change along the road 6 | 7 | Introduction 8 | ************ 9 | 10 | This project is a modification for Gaggia coffee machines replacing the 11 | existing thermostats with a PID controller powered by Arduino. 12 | This modification could be applied to other machines too, but 13 | in this document I will describe how I modified a ``Gaggia Paros``. 14 | The ``Gaggia Paros`` is almost identical in its parts to a ``Gaggia Classic`` and it comes 15 | combined with a coffee grinder. 16 | 17 | To add a PID controller to the coffee machine we'll need to replace the existing 18 | thermostats that control the heater. There are 2 thermostats to allow the operation 19 | of the machine heating water to brew temperature and also steam temperature. 20 | Unfortunately these thermostats do not allow a fine control of the water temperature, 21 | being a simple on/off switch without any logic behind. 22 | The result is that they don't keep the water/steam temperature stable enough to allow 23 | consistency of the brewed coffee. 24 | 25 | .. toctree:: 26 | :maxdepth: 1 27 | :numbered: 28 | :caption: Documentation 29 | 30 | src/documentation 31 | -------------------------------------------------------------------------------- /docs/make.bat: -------------------------------------------------------------------------------- 1 | @ECHO OFF 2 | 3 | pushd %~dp0 4 | 5 | REM Command file for Sphinx documentation 6 | 7 | if "%SPHINXBUILD%" == "" ( 8 | set SPHINXBUILD=sphinx-build 9 | ) 10 | set SOURCEDIR=. 11 | set BUILDDIR=_build 12 | 13 | if "%1" == "" goto help 14 | 15 | %SPHINXBUILD% >NUL 2>NUL 16 | if errorlevel 9009 ( 17 | echo. 18 | echo.The 'sphinx-build' command was not found. Make sure you have Sphinx 19 | echo.installed, then set the SPHINXBUILD environment variable to point 20 | echo.to the full path of the 'sphinx-build' executable. Alternatively you 21 | echo.may add the Sphinx directory to PATH. 22 | echo. 23 | echo.If you don't have Sphinx installed, grab it from 24 | echo.http://sphinx-doc.org/ 25 | exit /b 1 26 | ) 27 | 28 | %SPHINXBUILD% -M %1 %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% 29 | goto end 30 | 31 | :help 32 | %SPHINXBUILD% -M help %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% 33 | 34 | :end 35 | popd 36 | -------------------------------------------------------------------------------- /docs/misc/GaggiaPIDController.fzz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/misc/GaggiaPIDController.fzz -------------------------------------------------------------------------------- /docs/requirements.txt: -------------------------------------------------------------------------------- 1 | sphinx-rtd-theme 2 | sphinx -------------------------------------------------------------------------------- /docs/src/documentation.rst: -------------------------------------------------------------------------------- 1 | Overview 2 | ******** 3 | 4 | This is the electric diagram of the ``Gaggia Paros``: 5 | 6 | .. figure:: schematics/gaggia_paros_wiring.png 7 | :align: center 8 | :alt: Gaggia Paros electrical wiring 9 | 10 | Gaggia Paros electrical wiring 11 | 12 | The switches ``5`` and ``6`` represent the two thermostats that are going to be replaced 13 | with two temperature sensors and a Solid State Relay that the Arduino will 14 | use to control the heater. 15 | The second required modification is to connect the Arduino to the left pins of the 16 | "double switch" number ``13``. This will allow the Arduino to know if the Steam button 17 | has been pressed in order to target the correct temperature. 18 | 19 | This is the list of materials I used for this project. The purpose here is to just give 20 | an idea of what I used, you can change anything as you might prefer: 21 | 22 | * Temperature sensors (x2). I tried with both: 23 | * TSic 306 digital temperature sensor 24 | * K-type thermocouple with a MAX6675 ADC module 25 | * 128x64 OLED with SSD1306 controller 26 | * Arduino Nano 27 | * Arduino Nano expansion connection shield 28 | * Fotek clone SSR 40A 29 | * Wires 22AWG (low voltage) and 18AWG (AC line) 30 | * Heat shrinking sleeves 31 | * T-tap (scotch) connectors 32 | * Thermal paste 33 | * M4 brass hexagonal standoff 34 | 35 | This is the diagram of all the components connected for testing on a breadboard. 36 | In the diagram the thermocouple sensors are missing and their pins are to be considered 37 | as connected to the two MAX6675 modules. 38 | The same exception is true for the SSR AC pins. 39 | 40 | .. figure:: images/GaggiaPIDController_bb.jpg 41 | :align: center 42 | :alt: Breadboard circuit diagram 43 | 44 | Breadboard circuit diagram 45 | 46 | Arduino 47 | ******* 48 | 49 | I decided to use an Arduino Nano because of its small size and the USB port which 50 | is handy to upload sketches and interface with the Serial for debugging. 51 | I decided to not use a PCB as most of the components are far from each other and I wanted 52 | to allow easy plug and play of each module. 53 | I then connected the Arduino Nano to an expansion board that allows to connect wires 54 | with screw connectors without having to solder anything. 55 | I 3D printed a simple box to contain and isolate the Arduino from the machine frame. 56 | 57 | .. figure:: images/arduino_nano.jpg 58 | :align: center 59 | :alt: Arduino Nano and its expansion board 60 | 61 | Arduino Nano and its expansion board 62 | 63 | Temperature sensors 64 | ******************* 65 | 66 | I have tested this whole setup with two different types of sensors: 67 | 68 | * TSic306 69 | * K-type thermocouple 70 | 71 | TSic306 72 | ======= 73 | 74 | At first I decided to use the TSic 306 digital temperature sensors. As suggested 75 | in similar projects there are several benefits: it's digital so no need for ADC or 76 | external bridge boards, max operational temperature is +150deg C which is ok as the 77 | steam needs to get around 145deg C and it comes in a TO92 package which is quite compact. 78 | 79 | The main challenge I had with these sensors was fitting them in the heater: the 80 | stock thermostats are connected through a M4 screw, so following advice from other 81 | similar projects I bought a couple of brass hexagonal standoff with a M4 male thread and 82 | I tried to find a way to assemply the sensors into them. 83 | 84 | Unfortunately the TO92 package is 4.5mm wide so I used some sand paper to smooth the 85 | corners of the sensors, trying to not damage the internal wirings. Ideally I would 86 | have drilled the M4 female thread but I did not have a drill at hand :( 87 | 88 | I then filled the female thread with thermal paste and I inserted the sensors in the 89 | paste. Eventually I covered everything with a heat shrinking sleeve. 90 | 91 | .. figure:: images/temp_sensor_assembled.jpg 92 | :align: center 93 | :alt: Temperature sensor TSic306 assembled 94 | 95 | Temperature sensor TSic306 assembled 96 | 97 | This setup worked very well for several months until I had to do some maintenance to the 98 | machine: removing the heater to replace the solenoid valve I broke one of them. 99 | The problem with this solution was that the two sensors were not really stable 100 | in the brass standoff and it was easy to knock them off by touching them or pulling the 101 | wires. 102 | 103 | K-type thermocouple 104 | =================== 105 | 106 | I then decided to try out two K-type thermocouples. I bought two of those that 107 | come already assembled on an M4 nut (designed for 3D printers) which is handy as this was 108 | the weak point of the previous solution. 109 | 110 | The main drawback is that they require a voltage amplifier and an ADC to digitalise the 111 | signal. 112 | Fortunately both of these can be sourced in a single package, the MAX6675 module. 113 | The Arduino can "speak" with the MAX6675 with the SPI protocol requiring 2 more pins 114 | compared to the digital sensor solution. Not a big deal as there are plenty available. 115 | 116 | .. figure:: images/ktype_thermocouple.jpg 117 | :align: center 118 | :alt: K-type thermocouples assembled on the heater 119 | 120 | K-type thermocouples assembled on the heater 121 | 122 | .. figure:: images/max6675_module.jpg 123 | :align: center 124 | :alt: MAX6675 module 125 | 126 | MAX6675 module 127 | 128 | Another possible drawback with thermocouple is the error they might be subject to: 129 | again I was not really worried about this because even if there is a ~2deg C error, as 130 | long as it's stable (basically just an offset) it would not impact the PID performances. 131 | 132 | Solid State Relay 133 | ***************** 134 | 135 | I used one of the common (and cheap) Fotek clone SSR. From what I could read online 136 | these clones usually contain underrated triac, so to stay on the safe side I used the 137 | 40A version with the hope it's not going to blow up. 138 | This type of SSR can be controlled with a signal in the range 3-32 VDC and they update 139 | the output when the AC signal crosses its zero level. 140 | 141 | The SSR can be placed inside the coffee machine with it's metal back side on the coffee 142 | machine metal frame in order to dissipate any heat. The control signals are going to be 143 | wired to the Arduino board: one to ``GND`` and one to the selected digital pin. 144 | 145 | .. figure:: images/arduino_and_ssr.jpg 146 | :align: center 147 | :alt: Arduino Nano and the Fotek SSR 148 | 149 | Arduino Nano and the Fotek SSR 150 | 151 | The AC terminals instead needs to be connected to replace the two thermostats. One 152 | themostat is connected to a ``red`` and a ``brown`` wire, while the second one is 153 | connected to a ``white`` and again a ``red`` wire. I connected the SSR terminals using 154 | a piece of 18AWG wire and 2 male spade connectors, one to the ``brown`` connector 155 | of the first thermostat and the second one to the ``white`` connector of the other 156 | thermostat. 157 | 158 | .. figure:: images/ssr_connector.jpg 159 | :align: center 160 | :alt: Connection between SSR and the heater 161 | 162 | Connection between SSR and the heater 163 | 164 | Power supply 165 | ************ 166 | 167 | There might be different ways to power the "low voltage" electronic for this project, 168 | at first I thought to use AAA batteries as the overall consumption is very low and the 169 | whole circuit is on only for 30min a day in average. 170 | Eventually I decided to take power from the main AC source using T-Tap connectors and use 171 | an AC-DC switch converter (cheap from Ebay). 172 | 173 | .. figure:: images/ttap_connector.jpg 174 | :align: center 175 | :alt: TTap connector on AC power line 176 | 177 | TTap connector on AC power line 178 | 179 | Using the T-Tap connectors allowed me to not having to cut or solder almost anything, and 180 | everything can still be removed reverting the machine back to it's original state. 181 | 182 | Eventually I enclosed the whole circuit board in 3D printed plastic case leaving it inside 183 | the coffee machine, as far as possible from any other components. The 5V lines has been 184 | wired to reach the Arduino board and the temperature sensors. 185 | 186 | .. figure:: images/power_supply.jpg 187 | :align: center 188 | :alt: Power supply enclosure 189 | 190 | Power supply enclosure 191 | 192 | I also used two clamp wire connectors for the ``5V`` and ``GND`` bus, again this makes 193 | it easier and faster to assemble everything and swap components if required. 194 | 195 | .. figure:: images/clamp_wire_connecttors.jpg 196 | :align: center 197 | :alt: Clamp wire connectors for 5V and GND 198 | 199 | Clamp wire connectors for 5V and GND 200 | 201 | Display 202 | ******* 203 | 204 | There is not a constraint on what display you can use, in my case I chose an OLED 128x64. 205 | This display uses the ``SSD1306`` controller and you can find several Arduino libraries 206 | that let you interface with it. 207 | The main reason to choose this type of display was that it uses the I2C protocol so I 208 | only needed 2 Arduino pins to control it (plus 2 to power it up). 209 | 210 | Steam button 211 | ************ 212 | 213 | To detect the machine operation mode, the Arduino needs to be connected to the machine 214 | steam mode button. The button has 4 "pins", two by two isolated. It's important to 215 | disconnect the correct two connectors: those that where bypassing the water thermostat 216 | in order to use the steam thermostat which has a higher trigger temperature. The other 217 | two connectors are important because the control the solenoid valve. 218 | Use the circuit diagram to clarify any doubt. 219 | 220 | One of the two pins has to be connected to ``GND``, while the second goes to the 221 | selected Arduino input digital pin, which must be set to ``INPUT_PULLUP`` mode. 222 | 223 | Assembly 224 | ******** 225 | 226 | In this section I'll recap the steps I took from the beginning, until the final 227 | assembly with the PID controller installed in the coffee machine. 228 | 229 | Once gathered all the materials for initial testing I wired everything on a breadboard 230 | to verify that the code was working as expected: 231 | 232 | .. figure:: images/testbench01.jpg 233 | :align: center 234 | :alt: Testbench assembly 235 | 236 | Testbench assembly 237 | 238 | This also helped me to find a good starting point for the PID gains, at least better than 239 | leaving them set to ``1``. They have been tuned again once everything was connected to the 240 | machine heater. 241 | 242 | First I applied two T-Tap connectors to the main AC power line. one can be applied 243 | to the Neutral just after the input socket, but it's important to connect the second one 244 | **after** the main power button. This allows the Arduino to turn on only when the machine 245 | is on. 246 | 247 | The AC-DC converter can be placed into it's plastic container and the AC terminals can 248 | be connected to the two T-Tap connectors. The 5V output is going to be connected to the 249 | Arduino, the sensors and the display. 250 | 251 | I then assembled the temperature sensors by unscrewing the thermostats and replacing 252 | them with the two sensors. For the water sensor, the heater must be freed removing its 4 253 | screws that keeps it connected to the main group. 254 | 255 | I placed the Arduino Nano with the expansion board and a plastic enclosure in the only 256 | available space on the machine frame and I wired the 5V into the ``Vin`` pin, the ``GND`` 257 | and the temperature sensors signal wires. 258 | 259 | I then positioned the SSR near the coffee grinder, connecting it's DC terminals to ``GND`` 260 | and to the Arduino pin, for the AC terminals instead I used 18 AWG wire with male 261 | spade connectors, that have been connected as described in `Solid State Relay`_. 262 | 263 | I removed the two connectors from the steam mode button which where used to short circuit 264 | one of the thermostat. I used two T-Tap connectors as "female" spade connectors and I 265 | wired them to ``GND`` and the Arduino pin. 266 | 267 | Regarding the display, I decided to place it on the front of the machine, between 268 | the amin group and the grinder, where there is a small unused gap. I wired the I2C 269 | signals from the Arduino to the front of the machine and together if ``5V`` and ``GND`` 270 | from the power supply, I placed everything at the front of the machine. 271 | 272 | Eventually I checked I connected all the wires to the appropriate port in the Arduino 273 | expansion shield and then I placed the external enclosure on the coffee machine back. 274 | 275 | This is how the ``Gaggia Paros`` looks like after the modification. 276 | The inside: 277 | 278 | .. figure:: images/final_mod_inside.jpg 279 | :align: center 280 | :alt: Final internal assembly of the Gaggia Paros 281 | 282 | Final internal assembly of the Gaggia Paros 283 | 284 | And the outside: 285 | 286 | .. figure:: images/final_mod.jpg 287 | :align: center 288 | :alt: Final external assembly of the Gaggia Paros 289 | 290 | Final external assembly of the Gaggia Paros 291 | 292 | PID Tuning 293 | ********** 294 | 295 | The last step was improving the PID controller by tuning the gains in order to achieve 296 | the best possible control of the heater. 297 | There are several guides online that explain what each gain does and how to resolve 298 | specific issues, I am not expert so I won't cover this part. My suggestion is to get a 299 | basic understanding of how a PID controller works and then just try changing the gain 300 | values to see the effect. 301 | 302 | The Arduino code is configured by default to send the current machine status to the Serial 303 | Interface in a comma separated string format. 304 | In the repository ``tools`` directory there is a Python script that connects to 305 | the machine serial port ``/dev/ttyUSB0`` (a different port can be specified), reading 306 | these messages coming from the Arduino and plotting the water temperature on a graph. 307 | 308 | Having a real-time plot of the water temperature will help massively the PID tuning 309 | process, because you will clearly see the oscillations or the overshooting and it will 310 | be easier to correct them. 311 | 312 | .. figure:: images/pid_tuning_screenshot.png 313 | :align: center 314 | :alt: PID tuning temperature plot 315 | 316 | PID tuning temperature plot 317 | 318 | Improvements 319 | ************ 320 | 321 | After a few months of use, everything still seems to be working as expected. The coffee 322 | quality has certainly improved and it's more consistent than before, I really advise 323 | to apply such modification to any coffee machine! 324 | 325 | There are still a few things that I'd like to improve: 326 | 327 | - Improve the internal wiring, I did not do a good job on that front 328 | - Replace the Arduino Nano with a ESP8266 based board to have WiFi connectivity 329 | 330 | I hope these notes are useful to anybody attempting a similar modification and please 331 | submit Issues or PR on the GitHub repository. 332 | 333 | Enjoy the coffee! 334 | -------------------------------------------------------------------------------- /docs/src/images/GaggiaPIDController_bb.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/GaggiaPIDController_bb.jpg -------------------------------------------------------------------------------- /docs/src/images/arduino_and_ssr.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/arduino_and_ssr.jpg -------------------------------------------------------------------------------- /docs/src/images/arduino_nano.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/arduino_nano.jpg -------------------------------------------------------------------------------- /docs/src/images/clamp_wire_connecttors.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/clamp_wire_connecttors.jpg -------------------------------------------------------------------------------- /docs/src/images/final_mod.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/final_mod.jpg -------------------------------------------------------------------------------- /docs/src/images/final_mod_inside.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/final_mod_inside.jpg -------------------------------------------------------------------------------- /docs/src/images/ktype_thermocouple.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/ktype_thermocouple.jpg -------------------------------------------------------------------------------- /docs/src/images/max6675_module.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/max6675_module.jpg -------------------------------------------------------------------------------- /docs/src/images/pid_tuning_screenshot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/pid_tuning_screenshot.png -------------------------------------------------------------------------------- /docs/src/images/power_supply.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/power_supply.jpg -------------------------------------------------------------------------------- /docs/src/images/ssr_connector.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/ssr_connector.jpg -------------------------------------------------------------------------------- /docs/src/images/temp_sensor_assembled.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/temp_sensor_assembled.jpg -------------------------------------------------------------------------------- /docs/src/images/testbench01.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/testbench01.jpg -------------------------------------------------------------------------------- /docs/src/images/ttap_connector.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/images/ttap_connector.jpg -------------------------------------------------------------------------------- /docs/src/schematics/gaggia_paros_wiring.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ilcardella/ArduinoCoffeeMachine/6500452f4126cdf410e5850ad3272a5a0e2bc44f/docs/src/schematics/gaggia_paros_wiring.png -------------------------------------------------------------------------------- /scripts/build-project.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | 3 | set -euo pipefail 4 | 5 | # Validate input parameters 6 | if [[ $# -lt 2 ]]; then 7 | echo "Usage: ./build-project.sh [core] [board]" 8 | echo "Example: ./build-project.sh avr uno" 9 | exit 1 10 | fi 11 | CORE=$1 12 | BOARD=$2 13 | 14 | # Build the code for the input Arduino boards 15 | arduino-cli version 16 | arduino-cli core update-index 17 | arduino-cli core install arduino:$CORE 18 | arduino-cli core list 19 | # install libraries 20 | arduino-cli lib install "PID" 21 | arduino-cli lib install "TSIC" 22 | arduino-cli lib install "SSD1306Ascii" 23 | arduino-cli lib install "MAX6675 library" 24 | arduino-cli compile --fqbn arduino:$CORE:$BOARD CoffeeMachine/CoffeeMachine.ino 25 | -------------------------------------------------------------------------------- /tools/.flake8: -------------------------------------------------------------------------------- 1 | [flake8] 2 | ; ignore = E203, E266, E501, W503, F403 3 | ; max-line-length = 88 4 | ; max-complexity = 18 5 | ; select = B,C,E,F,W,T4,B9 6 | select = C,E,F,W,B,B950 7 | extend-ignore = E501 -------------------------------------------------------------------------------- /tools/poetry.lock: -------------------------------------------------------------------------------- 1 | [[package]] 2 | name = "appdirs" 3 | version = "1.4.4" 4 | description = "A small Python module for determining appropriate platform-specific dirs, e.g. a \"user data dir\"." 5 | category = "dev" 6 | optional = false 7 | python-versions = "*" 8 | 9 | [[package]] 10 | name = "attrs" 11 | version = "21.4.0" 12 | description = "Classes Without Boilerplate" 13 | category = "dev" 14 | optional = false 15 | python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" 16 | 17 | [package.extras] 18 | dev = ["cloudpickle", "coverage[toml] (>=5.0.2)", "furo", "hypothesis", "mypy", "pre-commit", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "six", "sphinx", "sphinx-notfound-page", "zope.interface"] 19 | docs = ["furo", "sphinx", "sphinx-notfound-page", "zope.interface"] 20 | tests = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "six", "zope.interface"] 21 | tests-no-zope = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "six"] 22 | 23 | [[package]] 24 | name = "black" 25 | version = "19.10b0" 26 | description = "The uncompromising code formatter." 27 | category = "dev" 28 | optional = false 29 | python-versions = ">=3.6" 30 | 31 | [package.dependencies] 32 | appdirs = "*" 33 | attrs = ">=18.1.0" 34 | click = ">=6.5" 35 | pathspec = ">=0.6,<1" 36 | regex = "*" 37 | toml = ">=0.9.4" 38 | typed-ast = ">=1.4.0" 39 | 40 | [package.extras] 41 | d = ["aiohttp (>=3.3.2)", "aiohttp-cors"] 42 | 43 | [[package]] 44 | name = "click" 45 | version = "8.0.3" 46 | description = "Composable command line interface toolkit" 47 | category = "dev" 48 | optional = false 49 | python-versions = ">=3.6" 50 | 51 | [package.dependencies] 52 | colorama = {version = "*", markers = "platform_system == \"Windows\""} 53 | 54 | [[package]] 55 | name = "colorama" 56 | version = "0.4.4" 57 | description = "Cross-platform colored terminal text." 58 | category = "dev" 59 | optional = false 60 | python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" 61 | 62 | [[package]] 63 | name = "cycler" 64 | version = "0.11.0" 65 | description = "Composable style cycles" 66 | category = "main" 67 | optional = false 68 | python-versions = ">=3.6" 69 | 70 | [[package]] 71 | name = "flake8" 72 | version = "3.9.2" 73 | description = "the modular source code checker: pep8 pyflakes and co" 74 | category = "dev" 75 | optional = false 76 | python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,>=2.7" 77 | 78 | [package.dependencies] 79 | mccabe = ">=0.6.0,<0.7.0" 80 | pycodestyle = ">=2.7.0,<2.8.0" 81 | pyflakes = ">=2.3.0,<2.4.0" 82 | 83 | [[package]] 84 | name = "fonttools" 85 | version = "4.29.0" 86 | description = "Tools to manipulate font files" 87 | category = "main" 88 | optional = false 89 | python-versions = ">=3.7" 90 | 91 | [package.extras] 92 | all = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "fs (>=2.2.0,<3)", "lxml (>=4.0,<5)", "lz4 (>=1.7.4.2)", "matplotlib", "munkres", "scipy", "skia-pathops (>=0.5.0)", "sympy", "unicodedata2 (>=14.0.0)", "xattr", "zopfli (>=0.1.4)"] 93 | graphite = ["lz4 (>=1.7.4.2)"] 94 | interpolatable = ["munkres", "scipy"] 95 | lxml = ["lxml (>=4.0,<5)"] 96 | pathops = ["skia-pathops (>=0.5.0)"] 97 | plot = ["matplotlib"] 98 | symfont = ["sympy"] 99 | type1 = ["xattr"] 100 | ufo = ["fs (>=2.2.0,<3)"] 101 | unicode = ["unicodedata2 (>=14.0.0)"] 102 | woff = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "zopfli (>=0.1.4)"] 103 | 104 | [[package]] 105 | name = "kiwisolver" 106 | version = "1.3.2" 107 | description = "A fast implementation of the Cassowary constraint solver" 108 | category = "main" 109 | optional = false 110 | python-versions = ">=3.7" 111 | 112 | [[package]] 113 | name = "matplotlib" 114 | version = "3.5.1" 115 | description = "Python plotting package" 116 | category = "main" 117 | optional = false 118 | python-versions = ">=3.7" 119 | 120 | [package.dependencies] 121 | cycler = ">=0.10" 122 | fonttools = ">=4.22.0" 123 | kiwisolver = ">=1.0.1" 124 | numpy = ">=1.17" 125 | packaging = ">=20.0" 126 | pillow = ">=6.2.0" 127 | pyparsing = ">=2.2.1" 128 | python-dateutil = ">=2.7" 129 | setuptools_scm = ">=4" 130 | 131 | [[package]] 132 | name = "mccabe" 133 | version = "0.6.1" 134 | description = "McCabe checker, plugin for flake8" 135 | category = "dev" 136 | optional = false 137 | python-versions = "*" 138 | 139 | [[package]] 140 | name = "numpy" 141 | version = "1.22.1" 142 | description = "NumPy is the fundamental package for array computing with Python." 143 | category = "main" 144 | optional = false 145 | python-versions = ">=3.8" 146 | 147 | [[package]] 148 | name = "packaging" 149 | version = "21.3" 150 | description = "Core utilities for Python packages" 151 | category = "main" 152 | optional = false 153 | python-versions = ">=3.6" 154 | 155 | [package.dependencies] 156 | pyparsing = ">=2.0.2,<3.0.5 || >3.0.5" 157 | 158 | [[package]] 159 | name = "pathspec" 160 | version = "0.9.0" 161 | description = "Utility library for gitignore style pattern matching of file paths." 162 | category = "dev" 163 | optional = false 164 | python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,>=2.7" 165 | 166 | [[package]] 167 | name = "pillow" 168 | version = "9.3.0" 169 | description = "Python Imaging Library (Fork)" 170 | category = "main" 171 | optional = false 172 | python-versions = ">=3.7" 173 | 174 | [package.extras] 175 | docs = ["furo", "olefile", "sphinx (>=2.4)", "sphinx-copybutton", "sphinx-issues (>=3.0.1)", "sphinx-removed-in", "sphinxext-opengraph"] 176 | tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "packaging", "pyroma", "pytest", "pytest-cov", "pytest-timeout"] 177 | 178 | [[package]] 179 | name = "pycodestyle" 180 | version = "2.7.0" 181 | description = "Python style guide checker" 182 | category = "dev" 183 | optional = false 184 | python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" 185 | 186 | [[package]] 187 | name = "pyflakes" 188 | version = "2.3.1" 189 | description = "passive checker of Python programs" 190 | category = "dev" 191 | optional = false 192 | python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" 193 | 194 | [[package]] 195 | name = "pyparsing" 196 | version = "3.0.7" 197 | description = "Python parsing module" 198 | category = "main" 199 | optional = false 200 | python-versions = ">=3.6" 201 | 202 | [package.extras] 203 | diagrams = ["jinja2", "railroad-diagrams"] 204 | 205 | [[package]] 206 | name = "pyserial" 207 | version = "3.5" 208 | description = "Python Serial Port Extension" 209 | category = "main" 210 | optional = false 211 | python-versions = "*" 212 | 213 | [package.extras] 214 | cp2110 = ["hidapi"] 215 | 216 | [[package]] 217 | name = "python-dateutil" 218 | version = "2.8.2" 219 | description = "Extensions to the standard Python datetime module" 220 | category = "main" 221 | optional = false 222 | python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,>=2.7" 223 | 224 | [package.dependencies] 225 | six = ">=1.5" 226 | 227 | [[package]] 228 | name = "regex" 229 | version = "2022.1.18" 230 | description = "Alternative regular expression module, to replace re." 231 | category = "dev" 232 | optional = false 233 | python-versions = "*" 234 | 235 | [[package]] 236 | name = "setuptools" 237 | version = "65.6.0" 238 | description = "Easily download, build, install, upgrade, and uninstall Python packages" 239 | category = "main" 240 | optional = false 241 | python-versions = ">=3.7" 242 | 243 | [package.extras] 244 | docs = ["furo", "jaraco.packaging (>=9)", "jaraco.tidelift (>=1.4)", "pygments-github-lexers (==0.0.5)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-favicon", "sphinx-hoverxref (<2)", "sphinx-inline-tabs", "sphinx-notfound-page (==0.8.3)", "sphinx-reredirects", "sphinxcontrib-towncrier"] 245 | testing = ["build[virtualenv]", "filelock (>=3.4.0)", "flake8 (<5)", "flake8-2020", "ini2toml[lite] (>=0.9)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "pip (>=19.1)", "pip-run (>=8.8)", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=1.3)", "pytest-flake8", "pytest-mypy (>=0.9.1)", "pytest-perf", "pytest-timeout", "pytest-xdist", "tomli-w (>=1.0.0)", "virtualenv (>=13.0.0)", "wheel"] 246 | testing-integration = ["build[virtualenv]", "filelock (>=3.4.0)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "pytest", "pytest-enabler", "pytest-xdist", "tomli", "virtualenv (>=13.0.0)", "wheel"] 247 | 248 | [[package]] 249 | name = "setuptools-scm" 250 | version = "6.4.2" 251 | description = "the blessed package to manage your versions by scm tags" 252 | category = "main" 253 | optional = false 254 | python-versions = ">=3.6" 255 | 256 | [package.dependencies] 257 | packaging = ">=20.0" 258 | setuptools = "*" 259 | tomli = ">=1.0.0" 260 | 261 | [package.extras] 262 | test = ["pytest (>=6.2)", "virtualenv (>20)"] 263 | toml = ["setuptools (>=42)"] 264 | 265 | [[package]] 266 | name = "six" 267 | version = "1.16.0" 268 | description = "Python 2 and 3 compatibility utilities" 269 | category = "main" 270 | optional = false 271 | python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*" 272 | 273 | [[package]] 274 | name = "toml" 275 | version = "0.10.2" 276 | description = "Python Library for Tom's Obvious, Minimal Language" 277 | category = "dev" 278 | optional = false 279 | python-versions = ">=2.6, !=3.0.*, !=3.1.*, !=3.2.*" 280 | 281 | [[package]] 282 | name = "tomli" 283 | version = "2.0.0" 284 | description = "A lil' TOML parser" 285 | category = "main" 286 | optional = false 287 | python-versions = ">=3.7" 288 | 289 | [[package]] 290 | name = "typed-ast" 291 | version = "1.5.2" 292 | description = "a fork of Python 2 and 3 ast modules with type comment support" 293 | category = "dev" 294 | optional = false 295 | python-versions = ">=3.6" 296 | 297 | [metadata] 298 | lock-version = "1.1" 299 | python-versions = "^3.8" 300 | content-hash = "aaddc2b24eb7e6dacb5ec2e5272630fea06d441f9b3dce785e5708f103feed1b" 301 | 302 | [metadata.files] 303 | appdirs = [ 304 | {file = "appdirs-1.4.4-py2.py3-none-any.whl", hash = "sha256:a841dacd6b99318a741b166adb07e19ee71a274450e68237b4650ca1055ab128"}, 305 | {file = "appdirs-1.4.4.tar.gz", hash = "sha256:7d5d0167b2b1ba821647616af46a749d1c653740dd0d2415100fe26e27afdf41"}, 306 | ] 307 | attrs = [ 308 | {file = "attrs-21.4.0-py2.py3-none-any.whl", hash = "sha256:2d27e3784d7a565d36ab851fe94887c5eccd6a463168875832a1be79c82828b4"}, 309 | {file = "attrs-21.4.0.tar.gz", hash = "sha256:626ba8234211db98e869df76230a137c4c40a12d72445c45d5f5b716f076e2fd"}, 310 | ] 311 | black = [ 312 | {file = "black-19.10b0-py36-none-any.whl", hash = "sha256:1b30e59be925fafc1ee4565e5e08abef6b03fe455102883820fe5ee2e4734e0b"}, 313 | {file = "black-19.10b0.tar.gz", hash = "sha256:c2edb73a08e9e0e6f65a0e6af18b059b8b1cdd5bef997d7a0b181df93dc81539"}, 314 | ] 315 | click = [ 316 | {file = "click-8.0.3-py3-none-any.whl", hash = "sha256:353f466495adaeb40b6b5f592f9f91cb22372351c84caeb068132442a4518ef3"}, 317 | {file = "click-8.0.3.tar.gz", hash = "sha256:410e932b050f5eed773c4cda94de75971c89cdb3155a72a0831139a79e5ecb5b"}, 318 | ] 319 | colorama = [ 320 | {file = "colorama-0.4.4-py2.py3-none-any.whl", hash = "sha256:9f47eda37229f68eee03b24b9748937c7dc3868f906e8ba69fbcbdd3bc5dc3e2"}, 321 | {file = "colorama-0.4.4.tar.gz", hash = "sha256:5941b2b48a20143d2267e95b1c2a7603ce057ee39fd88e7329b0c292aa16869b"}, 322 | ] 323 | cycler = [ 324 | {file = "cycler-0.11.0-py3-none-any.whl", hash = "sha256:3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3"}, 325 | {file = "cycler-0.11.0.tar.gz", hash = "sha256:9c87405839a19696e837b3b818fed3f5f69f16f1eec1a1ad77e043dcea9c772f"}, 326 | ] 327 | flake8 = [ 328 | {file = "flake8-3.9.2-py2.py3-none-any.whl", hash = "sha256:bf8fd333346d844f616e8d47905ef3a3384edae6b4e9beb0c5101e25e3110907"}, 329 | {file = "flake8-3.9.2.tar.gz", hash = "sha256:07528381786f2a6237b061f6e96610a4167b226cb926e2aa2b6b1d78057c576b"}, 330 | ] 331 | fonttools = [ 332 | {file = "fonttools-4.29.0-py3-none-any.whl", hash = "sha256:ed9496e5650b977a697c50ac99c8e8331f9eae3f99e5ae649623359103306dfe"}, 333 | {file = "fonttools-4.29.0.zip", hash = "sha256:f4834250db2c9855c3385459579dbb5cdf74349ab059ea0e619359b65ae72037"}, 334 | ] 335 | kiwisolver = [ 336 | {file = "kiwisolver-1.3.2-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:1d819553730d3c2724582124aee8a03c846ec4362ded1034c16fb3ef309264e6"}, 337 | {file = "kiwisolver-1.3.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:8d93a1095f83e908fc253f2fb569c2711414c0bfd451cab580466465b235b470"}, 338 | {file = "kiwisolver-1.3.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c4550a359c5157aaf8507e6820d98682872b9100ce7607f8aa070b4b8af6c298"}, 339 | {file = "kiwisolver-1.3.2-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:2210f28778c7d2ee13f3c2a20a3a22db889e75f4ec13a21072eabb5693801e84"}, 340 | {file = "kiwisolver-1.3.2-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:82f49c5a79d3839bc8f38cb5f4bfc87e15f04cbafa5fbd12fb32c941cb529cfb"}, 341 | {file = "kiwisolver-1.3.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9661a04ca3c950a8ac8c47f53cbc0b530bce1b52f516a1e87b7736fec24bfff0"}, 342 | {file = "kiwisolver-1.3.2-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:2ddb500a2808c100e72c075cbb00bf32e62763c82b6a882d403f01a119e3f402"}, 343 | {file = "kiwisolver-1.3.2-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:72be6ebb4e92520b9726d7146bc9c9b277513a57a38efcf66db0620aec0097e0"}, 344 | {file = "kiwisolver-1.3.2-cp310-cp310-win32.whl", hash = "sha256:83d2c9db5dfc537d0171e32de160461230eb14663299b7e6d18ca6dca21e4977"}, 345 | {file = "kiwisolver-1.3.2-cp310-cp310-win_amd64.whl", hash = "sha256:cba430db673c29376135e695c6e2501c44c256a81495da849e85d1793ee975ad"}, 346 | {file = "kiwisolver-1.3.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:4116ba9a58109ed5e4cb315bdcbff9838f3159d099ba5259c7c7fb77f8537492"}, 347 | {file = "kiwisolver-1.3.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:19554bd8d54cf41139f376753af1a644b63c9ca93f8f72009d50a2080f870f77"}, 348 | {file = "kiwisolver-1.3.2-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a7a4cf5bbdc861987a7745aed7a536c6405256853c94abc9f3287c3fa401b174"}, 349 | {file = "kiwisolver-1.3.2-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0007840186bacfaa0aba4466d5890334ea5938e0bb7e28078a0eb0e63b5b59d5"}, 350 | {file = "kiwisolver-1.3.2-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:ec2eba188c1906b05b9b49ae55aae4efd8150c61ba450e6721f64620c50b59eb"}, 351 | {file = "kiwisolver-1.3.2-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:3dbb3cea20b4af4f49f84cffaf45dd5f88e8594d18568e0225e6ad9dec0e7967"}, 352 | {file = "kiwisolver-1.3.2-cp37-cp37m-win32.whl", hash = "sha256:5326ddfacbe51abf9469fe668944bc2e399181a2158cb5d45e1d40856b2a0589"}, 353 | {file = "kiwisolver-1.3.2-cp37-cp37m-win_amd64.whl", hash = "sha256:c6572c2dab23c86a14e82c245473d45b4c515314f1f859e92608dcafbd2f19b8"}, 354 | {file = "kiwisolver-1.3.2-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:b5074fb09429f2b7bc82b6fb4be8645dcbac14e592128beeff5461dcde0af09f"}, 355 | {file = "kiwisolver-1.3.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:22521219ca739654a296eea6d4367703558fba16f98688bd8ce65abff36eaa84"}, 356 | {file = "kiwisolver-1.3.2-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:c358721aebd40c243894298f685a19eb0491a5c3e0b923b9f887ef1193ddf829"}, 357 | {file = "kiwisolver-1.3.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7ba5a1041480c6e0a8b11a9544d53562abc2d19220bfa14133e0cdd9967e97af"}, 358 | {file = "kiwisolver-1.3.2-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:44e6adf67577dbdfa2d9f06db9fbc5639afefdb5bf2b4dfec25c3a7fbc619536"}, 359 | {file = "kiwisolver-1.3.2-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1d45d1c74f88b9f41062716c727f78f2a59a5476ecbe74956fafb423c5c87a76"}, 360 | {file = "kiwisolver-1.3.2-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:70adc3658138bc77a36ce769f5f183169bc0a2906a4f61f09673f7181255ac9b"}, 361 | {file = "kiwisolver-1.3.2-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:b6a5431940f28b6de123de42f0eb47b84a073ee3c3345dc109ad550a3307dd28"}, 362 | {file = "kiwisolver-1.3.2-cp38-cp38-win32.whl", hash = "sha256:ee040a7de8d295dbd261ef2d6d3192f13e2b08ec4a954de34a6fb8ff6422e24c"}, 363 | {file = "kiwisolver-1.3.2-cp38-cp38-win_amd64.whl", hash = "sha256:8dc3d842fa41a33fe83d9f5c66c0cc1f28756530cd89944b63b072281e852031"}, 364 | {file = "kiwisolver-1.3.2-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:a498bcd005e8a3fedd0022bb30ee0ad92728154a8798b703f394484452550507"}, 365 | {file = "kiwisolver-1.3.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:80efd202108c3a4150e042b269f7c78643420cc232a0a771743bb96b742f838f"}, 366 | {file = "kiwisolver-1.3.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:f8eb7b6716f5b50e9c06207a14172cf2de201e41912ebe732846c02c830455b9"}, 367 | {file = "kiwisolver-1.3.2-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f441422bb313ab25de7b3dbfd388e790eceb76ce01a18199ec4944b369017009"}, 368 | {file = "kiwisolver-1.3.2-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:30fa008c172355c7768159983a7270cb23838c4d7db73d6c0f6b60dde0d432c6"}, 369 | {file = "kiwisolver-1.3.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2f8f6c8f4f1cff93ca5058d6ec5f0efda922ecb3f4c5fb76181f327decff98b8"}, 370 | {file = "kiwisolver-1.3.2-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ba677bcaff9429fd1bf01648ad0901cea56c0d068df383d5f5856d88221fe75b"}, 371 | {file = "kiwisolver-1.3.2-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7843b1624d6ccca403a610d1277f7c28ad184c5aa88a1750c1a999754e65b439"}, 372 | {file = "kiwisolver-1.3.2-cp39-cp39-win32.whl", hash = "sha256:e6f5eb2f53fac7d408a45fbcdeda7224b1cfff64919d0f95473420a931347ae9"}, 373 | {file = "kiwisolver-1.3.2-cp39-cp39-win_amd64.whl", hash = "sha256:eedd3b59190885d1ebdf6c5e0ca56828beb1949b4dfe6e5d0256a461429ac386"}, 374 | {file = "kiwisolver-1.3.2-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:dedc71c8eb9c5096037766390172c34fb86ef048b8e8958b4e484b9e505d66bc"}, 375 | {file = "kiwisolver-1.3.2-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:bf7eb45d14fc036514c09554bf983f2a72323254912ed0c3c8e697b62c4c158f"}, 376 | {file = "kiwisolver-1.3.2-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:2b65bd35f3e06a47b5c30ea99e0c2b88f72c6476eedaf8cfbc8e66adb5479dcf"}, 377 | {file = "kiwisolver-1.3.2-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:25405f88a37c5f5bcba01c6e350086d65e7465fd1caaf986333d2a045045a223"}, 378 | {file = "kiwisolver-1.3.2-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:bcadb05c3d4794eb9eee1dddf1c24215c92fb7b55a80beae7a60530a91060560"}, 379 | {file = "kiwisolver-1.3.2.tar.gz", hash = "sha256:fc4453705b81d03568d5b808ad8f09c77c47534f6ac2e72e733f9ca4714aa75c"}, 380 | ] 381 | matplotlib = [ 382 | {file = "matplotlib-3.5.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:456cc8334f6d1124e8ff856b42d2cc1c84335375a16448189999496549f7182b"}, 383 | {file = "matplotlib-3.5.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:8a77906dc2ef9b67407cec0bdbf08e3971141e535db888974a915be5e1e3efc6"}, 384 | {file = "matplotlib-3.5.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8e70ae6475cfd0fad3816dcbf6cac536dc6f100f7474be58d59fa306e6e768a4"}, 385 | {file = "matplotlib-3.5.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:53273c5487d1c19c3bc03b9eb82adaf8456f243b97ed79d09dded747abaf1235"}, 386 | {file = "matplotlib-3.5.1-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e3b6f3fd0d8ca37861c31e9a7cab71a0ef14c639b4c95654ea1dd153158bf0df"}, 387 | {file = "matplotlib-3.5.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e8c87cdaf06fd7b2477f68909838ff4176f105064a72ca9d24d3f2a29f73d393"}, 388 | {file = "matplotlib-3.5.1-cp310-cp310-win32.whl", hash = "sha256:e2f28a07b4f82abb40267864ad7b3a4ed76f1b1663e81c7efc84a9b9248f672f"}, 389 | {file = "matplotlib-3.5.1-cp310-cp310-win_amd64.whl", hash = "sha256:d70a32ee1f8b55eed3fd4e892f0286df8cccc7e0475c11d33b5d0a148f5c7599"}, 390 | {file = "matplotlib-3.5.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:68fa30cec89b6139dc559ed6ef226c53fd80396da1919a1b5ef672c911aaa767"}, 391 | {file = "matplotlib-3.5.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2e3484d8455af3fdb0424eae1789af61f6a79da0c80079125112fd5c1b604218"}, 392 | {file = "matplotlib-3.5.1-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:e293b16cf303fe82995e41700d172a58a15efc5331125d08246b520843ef21ee"}, 393 | {file = "matplotlib-3.5.1-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:e3520a274a0e054e919f5b3279ee5dbccf5311833819ccf3399dab7c83e90a25"}, 394 | {file = "matplotlib-3.5.1-cp37-cp37m-win32.whl", hash = "sha256:2252bfac85cec7af4a67e494bfccf9080bcba8a0299701eab075f48847cca907"}, 395 | {file = "matplotlib-3.5.1-cp37-cp37m-win_amd64.whl", hash = "sha256:abf67e05a1b7f86583f6ebd01f69b693b9c535276f4e943292e444855870a1b8"}, 396 | {file = "matplotlib-3.5.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:6c094e4bfecd2fa7f9adffd03d8abceed7157c928c2976899de282f3600f0a3d"}, 397 | {file = "matplotlib-3.5.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:506b210cc6e66a0d1c2bb765d055f4f6bc2745070fb1129203b67e85bbfa5c18"}, 398 | {file = "matplotlib-3.5.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b04fc29bcef04d4e2d626af28d9d892be6aba94856cb46ed52bcb219ceac8943"}, 399 | {file = "matplotlib-3.5.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:577ed20ec9a18d6bdedb4616f5e9e957b4c08563a9f985563a31fd5b10564d2a"}, 400 | {file = "matplotlib-3.5.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:e486f60db0cd1c8d68464d9484fd2a94011c1ac8593d765d0211f9daba2bd535"}, 401 | {file = "matplotlib-3.5.1-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:b71f3a7ca935fc759f2aed7cec06cfe10bc3100fadb5dbd9c435b04e557971e1"}, 402 | {file = "matplotlib-3.5.1-cp38-cp38-win32.whl", hash = "sha256:d24e5bb8028541ce25e59390122f5e48c8506b7e35587e5135efcb6471b4ac6c"}, 403 | {file = "matplotlib-3.5.1-cp38-cp38-win_amd64.whl", hash = "sha256:778d398c4866d8e36ee3bf833779c940b5f57192fa0a549b3ad67bc4c822771b"}, 404 | {file = "matplotlib-3.5.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:bb1c613908f11bac270bc7494d68b1ef6e7c224b7a4204d5dacf3522a41e2bc3"}, 405 | {file = "matplotlib-3.5.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:edf5e4e1d5fb22c18820e8586fb867455de3b109c309cb4fce3aaed85d9468d1"}, 406 | {file = "matplotlib-3.5.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:40e0d7df05e8efe60397c69b467fc8f87a2affeb4d562fe92b72ff8937a2b511"}, 407 | {file = "matplotlib-3.5.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7a350ca685d9f594123f652ba796ee37219bf72c8e0fc4b471473d87121d6d34"}, 408 | {file = "matplotlib-3.5.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:3e66497cd990b1a130e21919b004da2f1dc112132c01ac78011a90a0f9229778"}, 409 | {file = "matplotlib-3.5.1-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:87900c67c0f1728e6db17c6809ec05c025c6624dcf96a8020326ea15378fe8e7"}, 410 | {file = "matplotlib-3.5.1-cp39-cp39-win32.whl", hash = "sha256:b8a4fb2a0c5afbe9604f8a91d7d0f27b1832c3e0b5e365f95a13015822b4cd65"}, 411 | {file = "matplotlib-3.5.1-cp39-cp39-win_amd64.whl", hash = "sha256:fe8d40c434a8e2c68d64c6d6a04e77f21791a93ff6afe0dce169597c110d3079"}, 412 | {file = "matplotlib-3.5.1-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:34a1fc29f8f96e78ec57a5eff5e8d8b53d3298c3be6df61e7aa9efba26929522"}, 413 | {file = "matplotlib-3.5.1-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:b19a761b948e939a9e20173aaae76070025f0024fc8f7ba08bef22a5c8573afc"}, 414 | {file = "matplotlib-3.5.1-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:6803299cbf4665eca14428d9e886de62e24f4223ac31ab9c5d6d5339a39782c7"}, 415 | {file = "matplotlib-3.5.1-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:14334b9902ec776461c4b8c6516e26b450f7ebe0b3ef8703bf5cdfbbaecf774a"}, 416 | {file = "matplotlib-3.5.1.tar.gz", hash = "sha256:b2e9810e09c3a47b73ce9cab5a72243a1258f61e7900969097a817232246ce1c"}, 417 | ] 418 | mccabe = [ 419 | {file = "mccabe-0.6.1-py2.py3-none-any.whl", hash = "sha256:ab8a6258860da4b6677da4bd2fe5dc2c659cff31b3ee4f7f5d64e79735b80d42"}, 420 | {file = "mccabe-0.6.1.tar.gz", hash = "sha256:dd8d182285a0fe56bace7f45b5e7d1a6ebcbf524e8f3bd87eb0f125271b8831f"}, 421 | ] 422 | numpy = [ 423 | {file = "numpy-1.22.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:3d62d6b0870b53799204515145935608cdeb4cebb95a26800b6750e48884cc5b"}, 424 | {file = "numpy-1.22.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:831f2df87bd3afdfc77829bc94bd997a7c212663889d56518359c827d7113b1f"}, 425 | {file = "numpy-1.22.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8d1563060e77096367952fb44fca595f2b2f477156de389ce7c0ade3aef29e21"}, 426 | {file = "numpy-1.22.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:69958735d5e01f7b38226a6c6e7187d72b7e4d42b6b496aca5860b611ca0c193"}, 427 | {file = "numpy-1.22.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:45a7dfbf9ed8d68fd39763940591db7637cf8817c5bce1a44f7b56c97cbe211e"}, 428 | {file = "numpy-1.22.1-cp310-cp310-win_amd64.whl", hash = "sha256:7e957ca8112c689b728037cea9c9567c27cf912741fabda9efc2c7d33d29dfa1"}, 429 | {file = "numpy-1.22.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:800dfeaffb2219d49377da1371d710d7952c9533b57f3d51b15e61c4269a1b5b"}, 430 | {file = "numpy-1.22.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:65f5e257987601fdfc63f1d02fca4d1c44a2b85b802f03bd6abc2b0b14648dd2"}, 431 | {file = "numpy-1.22.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:632e062569b0fe05654b15ef0e91a53c0a95d08ffe698b66f6ba0f927ad267c2"}, 432 | {file = "numpy-1.22.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0d245a2bf79188d3f361137608c3cd12ed79076badd743dc660750a9f3074f7c"}, 433 | {file = "numpy-1.22.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:26b4018a19d2ad9606ce9089f3d52206a41b23de5dfe8dc947d2ec49ce45d015"}, 434 | {file = "numpy-1.22.1-cp38-cp38-win32.whl", hash = "sha256:f8ad59e6e341f38266f1549c7c2ec70ea0e3d1effb62a44e5c3dba41c55f0187"}, 435 | {file = "numpy-1.22.1-cp38-cp38-win_amd64.whl", hash = "sha256:60f19c61b589d44fbbab8ff126640ae712e163299c2dd422bfe4edc7ec51aa9b"}, 436 | {file = "numpy-1.22.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:2db01d9838a497ba2aa9a87515aeaf458f42351d72d4e7f3b8ddbd1eba9479f2"}, 437 | {file = "numpy-1.22.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:bcd19dab43b852b03868796f533b5f5561e6c0e3048415e675bec8d2e9d286c1"}, 438 | {file = "numpy-1.22.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:78bfbdf809fc236490e7e65715bbd98377b122f329457fffde206299e163e7f3"}, 439 | {file = "numpy-1.22.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c51124df17f012c3b757380782ae46eee85213a3215e51477e559739f57d9bf6"}, 440 | {file = "numpy-1.22.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:88d54b7b516f0ca38a69590557814de2dd638d7d4ed04864826acaac5ebb8f01"}, 441 | {file = "numpy-1.22.1-cp39-cp39-win32.whl", hash = "sha256:b5ec9a5eaf391761c61fd873363ef3560a3614e9b4ead17347e4deda4358bca4"}, 442 | {file = "numpy-1.22.1-cp39-cp39-win_amd64.whl", hash = "sha256:4ac4d7c9f8ea2a79d721ebfcce81705fc3cd61a10b731354f1049eb8c99521e8"}, 443 | {file = "numpy-1.22.1-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e60ef82c358ded965fdd3132b5738eade055f48067ac8a5a8ac75acc00cad31f"}, 444 | {file = "numpy-1.22.1.zip", hash = "sha256:e348ccf5bc5235fc405ab19d53bec215bb373300e5523c7b476cc0da8a5e9973"}, 445 | ] 446 | packaging = [ 447 | {file = "packaging-21.3-py3-none-any.whl", hash = "sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522"}, 448 | {file = "packaging-21.3.tar.gz", hash = "sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb"}, 449 | ] 450 | pathspec = [ 451 | {file = "pathspec-0.9.0-py2.py3-none-any.whl", hash = "sha256:7d15c4ddb0b5c802d161efc417ec1a2558ea2653c2e8ad9c19098201dc1c993a"}, 452 | {file = "pathspec-0.9.0.tar.gz", hash = "sha256:e564499435a2673d586f6b2130bb5b95f04a3ba06f81b8f895b651a3c76aabb1"}, 453 | ] 454 | pillow = [ 455 | {file = "Pillow-9.3.0-1-cp37-cp37m-win32.whl", hash = "sha256:e6ea6b856a74d560d9326c0f5895ef8050126acfdc7ca08ad703eb0081e82b74"}, 456 | {file = "Pillow-9.3.0-1-cp37-cp37m-win_amd64.whl", hash = "sha256:32a44128c4bdca7f31de5be641187367fe2a450ad83b833ef78910397db491aa"}, 457 | {file = "Pillow-9.3.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:0b7257127d646ff8676ec8a15520013a698d1fdc48bc2a79ba4e53df792526f2"}, 458 | {file = "Pillow-9.3.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:b90f7616ea170e92820775ed47e136208e04c967271c9ef615b6fbd08d9af0e3"}, 459 | {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:68943d632f1f9e3dce98908e873b3a090f6cba1cbb1b892a9e8d97c938871fbe"}, 460 | {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:be55f8457cd1eac957af0c3f5ece7bc3f033f89b114ef30f710882717670b2a8"}, 461 | {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5d77adcd56a42d00cc1be30843d3426aa4e660cab4a61021dc84467123f7a00c"}, 462 | {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:829f97c8e258593b9daa80638aee3789b7df9da5cf1336035016d76f03b8860c"}, 463 | {file = "Pillow-9.3.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:801ec82e4188e935c7f5e22e006d01611d6b41661bba9fe45b60e7ac1a8f84de"}, 464 | {file = "Pillow-9.3.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:871b72c3643e516db4ecf20efe735deb27fe30ca17800e661d769faab45a18d7"}, 465 | {file = "Pillow-9.3.0-cp310-cp310-win32.whl", hash = "sha256:655a83b0058ba47c7c52e4e2df5ecf484c1b0b0349805896dd350cbc416bdd91"}, 466 | {file = "Pillow-9.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:9f47eabcd2ded7698106b05c2c338672d16a6f2a485e74481f524e2a23c2794b"}, 467 | {file = "Pillow-9.3.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:57751894f6618fd4308ed8e0c36c333e2f5469744c34729a27532b3db106ee20"}, 468 | {file = "Pillow-9.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7db8b751ad307d7cf238f02101e8e36a128a6cb199326e867d1398067381bff4"}, 469 | {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3033fbe1feb1b59394615a1cafaee85e49d01b51d54de0cbf6aa8e64182518a1"}, 470 | {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:22b012ea2d065fd163ca096f4e37e47cd8b59cf4b0fd47bfca6abb93df70b34c"}, 471 | {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b9a65733d103311331875c1dca05cb4606997fd33d6acfed695b1232ba1df193"}, 472 | {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:502526a2cbfa431d9fc2a079bdd9061a2397b842bb6bc4239bb176da00993812"}, 473 | {file = "Pillow-9.3.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:90fb88843d3902fe7c9586d439d1e8c05258f41da473952aa8b328d8b907498c"}, 474 | {file = "Pillow-9.3.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:89dca0ce00a2b49024df6325925555d406b14aa3efc2f752dbb5940c52c56b11"}, 475 | {file = "Pillow-9.3.0-cp311-cp311-win32.whl", hash = "sha256:3168434d303babf495d4ba58fc22d6604f6e2afb97adc6a423e917dab828939c"}, 476 | {file = "Pillow-9.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:18498994b29e1cf86d505edcb7edbe814d133d2232d256db8c7a8ceb34d18cef"}, 477 | {file = "Pillow-9.3.0-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:772a91fc0e03eaf922c63badeca75e91baa80fe2f5f87bdaed4280662aad25c9"}, 478 | {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:afa4107d1b306cdf8953edde0534562607fe8811b6c4d9a486298ad31de733b2"}, 479 | {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b4012d06c846dc2b80651b120e2cdd787b013deb39c09f407727ba90015c684f"}, 480 | {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:77ec3e7be99629898c9a6d24a09de089fa5356ee408cdffffe62d67bb75fdd72"}, 481 | {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_28_aarch64.whl", hash = "sha256:6c738585d7a9961d8c2821a1eb3dcb978d14e238be3d70f0a706f7fa9316946b"}, 482 | {file = "Pillow-9.3.0-cp37-cp37m-manylinux_2_28_x86_64.whl", hash = "sha256:828989c45c245518065a110434246c44a56a8b2b2f6347d1409c787e6e4651ee"}, 483 | {file = "Pillow-9.3.0-cp37-cp37m-win32.whl", hash = "sha256:82409ffe29d70fd733ff3c1025a602abb3e67405d41b9403b00b01debc4c9a29"}, 484 | {file = "Pillow-9.3.0-cp37-cp37m-win_amd64.whl", hash = "sha256:41e0051336807468be450d52b8edd12ac60bebaa97fe10c8b660f116e50b30e4"}, 485 | {file = "Pillow-9.3.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:b03ae6f1a1878233ac620c98f3459f79fd77c7e3c2b20d460284e1fb370557d4"}, 486 | {file = "Pillow-9.3.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:4390e9ce199fc1951fcfa65795f239a8a4944117b5935a9317fb320e7767b40f"}, 487 | {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:40e1ce476a7804b0fb74bcfa80b0a2206ea6a882938eaba917f7a0f004b42502"}, 488 | {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a0a06a052c5f37b4ed81c613a455a81f9a3a69429b4fd7bb913c3fa98abefc20"}, 489 | {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:03150abd92771742d4a8cd6f2fa6246d847dcd2e332a18d0c15cc75bf6703040"}, 490 | {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:15c42fb9dea42465dfd902fb0ecf584b8848ceb28b41ee2b58f866411be33f07"}, 491 | {file = "Pillow-9.3.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:51e0e543a33ed92db9f5ef69a0356e0b1a7a6b6a71b80df99f1d181ae5875636"}, 492 | {file = "Pillow-9.3.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:3dd6caf940756101205dffc5367babf288a30043d35f80936f9bfb37f8355b32"}, 493 | {file = "Pillow-9.3.0-cp38-cp38-win32.whl", hash = "sha256:f1ff2ee69f10f13a9596480335f406dd1f70c3650349e2be67ca3139280cade0"}, 494 | {file = "Pillow-9.3.0-cp38-cp38-win_amd64.whl", hash = "sha256:276a5ca930c913f714e372b2591a22c4bd3b81a418c0f6635ba832daec1cbcfc"}, 495 | {file = "Pillow-9.3.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:73bd195e43f3fadecfc50c682f5055ec32ee2c933243cafbfdec69ab1aa87cad"}, 496 | {file = "Pillow-9.3.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:1c7c8ae3864846fc95f4611c78129301e203aaa2af813b703c55d10cc1628535"}, 497 | {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2e0918e03aa0c72ea56edbb00d4d664294815aa11291a11504a377ea018330d3"}, 498 | {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b0915e734b33a474d76c28e07292f196cdf2a590a0d25bcc06e64e545f2d146c"}, 499 | {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:af0372acb5d3598f36ec0914deed2a63f6bcdb7b606da04dc19a88d31bf0c05b"}, 500 | {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:ad58d27a5b0262c0c19b47d54c5802db9b34d38bbf886665b626aff83c74bacd"}, 501 | {file = "Pillow-9.3.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:97aabc5c50312afa5e0a2b07c17d4ac5e865b250986f8afe2b02d772567a380c"}, 502 | {file = "Pillow-9.3.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:9aaa107275d8527e9d6e7670b64aabaaa36e5b6bd71a1015ddd21da0d4e06448"}, 503 | {file = "Pillow-9.3.0-cp39-cp39-win32.whl", hash = "sha256:bac18ab8d2d1e6b4ce25e3424f709aceef668347db8637c2296bcf41acb7cf48"}, 504 | {file = "Pillow-9.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:b472b5ea442148d1c3e2209f20f1e0bb0eb556538690fa70b5e1f79fa0ba8dc2"}, 505 | {file = "Pillow-9.3.0-pp37-pypy37_pp73-macosx_10_10_x86_64.whl", hash = "sha256:ab388aaa3f6ce52ac1cb8e122c4bd46657c15905904b3120a6248b5b8b0bc228"}, 506 | {file = "Pillow-9.3.0-pp37-pypy37_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dbb8e7f2abee51cef77673be97760abff1674ed32847ce04b4af90f610144c7b"}, 507 | {file = "Pillow-9.3.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bca31dd6014cb8b0b2db1e46081b0ca7d936f856da3b39744aef499db5d84d02"}, 508 | {file = "Pillow-9.3.0-pp37-pypy37_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:c7025dce65566eb6e89f56c9509d4f628fddcedb131d9465cacd3d8bac337e7e"}, 509 | {file = "Pillow-9.3.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:ebf2029c1f464c59b8bdbe5143c79fa2045a581ac53679733d3a91d400ff9efb"}, 510 | {file = "Pillow-9.3.0-pp38-pypy38_pp73-macosx_10_10_x86_64.whl", hash = "sha256:b59430236b8e58840a0dfb4099a0e8717ffb779c952426a69ae435ca1f57210c"}, 511 | {file = "Pillow-9.3.0-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:12ce4932caf2ddf3e41d17fc9c02d67126935a44b86df6a206cf0d7161548627"}, 512 | {file = "Pillow-9.3.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ae5331c23ce118c53b172fa64a4c037eb83c9165aba3a7ba9ddd3ec9fa64a699"}, 513 | {file = "Pillow-9.3.0-pp38-pypy38_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:0b07fffc13f474264c336298d1b4ce01d9c5a011415b79d4ee5527bb69ae6f65"}, 514 | {file = "Pillow-9.3.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:073adb2ae23431d3b9bcbcff3fe698b62ed47211d0716b067385538a1b0f28b8"}, 515 | {file = "Pillow-9.3.0.tar.gz", hash = "sha256:c935a22a557a560108d780f9a0fc426dd7459940dc54faa49d83249c8d3e760f"}, 516 | ] 517 | pycodestyle = [ 518 | {file = "pycodestyle-2.7.0-py2.py3-none-any.whl", hash = "sha256:514f76d918fcc0b55c6680472f0a37970994e07bbb80725808c17089be302068"}, 519 | {file = "pycodestyle-2.7.0.tar.gz", hash = "sha256:c389c1d06bf7904078ca03399a4816f974a1d590090fecea0c63ec26ebaf1cef"}, 520 | ] 521 | pyflakes = [ 522 | {file = "pyflakes-2.3.1-py2.py3-none-any.whl", hash = "sha256:7893783d01b8a89811dd72d7dfd4d84ff098e5eed95cfa8905b22bbffe52efc3"}, 523 | {file = "pyflakes-2.3.1.tar.gz", hash = "sha256:f5bc8ecabc05bb9d291eb5203d6810b49040f6ff446a756326104746cc00c1db"}, 524 | ] 525 | pyparsing = [ 526 | {file = "pyparsing-3.0.7-py3-none-any.whl", hash = "sha256:a6c06a88f252e6c322f65faf8f418b16213b51bdfaece0524c1c1bc30c63c484"}, 527 | {file = "pyparsing-3.0.7.tar.gz", hash = "sha256:18ee9022775d270c55187733956460083db60b37d0d0fb357445f3094eed3eea"}, 528 | ] 529 | pyserial = [ 530 | {file = "pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0"}, 531 | {file = "pyserial-3.5.tar.gz", hash = "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb"}, 532 | ] 533 | python-dateutil = [ 534 | {file = "python-dateutil-2.8.2.tar.gz", hash = "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86"}, 535 | {file = "python_dateutil-2.8.2-py2.py3-none-any.whl", hash = "sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9"}, 536 | ] 537 | regex = [ 538 | {file = "regex-2022.1.18-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:34316bf693b1d2d29c087ee7e4bb10cdfa39da5f9c50fa15b07489b4ab93a1b5"}, 539 | {file = "regex-2022.1.18-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:7a0b9f6a1a15d494b35f25ed07abda03209fa76c33564c09c9e81d34f4b919d7"}, 540 | {file = "regex-2022.1.18-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f99112aed4fb7cee00c7f77e8b964a9b10f69488cdff626ffd797d02e2e4484f"}, 541 | {file = "regex-2022.1.18-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9a2bf98ac92f58777c0fafc772bf0493e67fcf677302e0c0a630ee517a43b949"}, 542 | {file = "regex-2022.1.18-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8618d9213a863c468a865e9d2ec50221015f7abf52221bc927152ef26c484b4c"}, 543 | {file = "regex-2022.1.18-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b52cc45e71657bc4743a5606d9023459de929b2a198d545868e11898ba1c3f59"}, 544 | {file = "regex-2022.1.18-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7e12949e5071c20ec49ef00c75121ed2b076972132fc1913ddf5f76cae8d10b4"}, 545 | {file = "regex-2022.1.18-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:b02e3e72665cd02afafb933453b0c9f6c59ff6e3708bd28d0d8580450e7e88af"}, 546 | {file = "regex-2022.1.18-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:abfcb0ef78df0ee9df4ea81f03beea41849340ce33a4c4bd4dbb99e23ec781b6"}, 547 | {file = "regex-2022.1.18-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:6213713ac743b190ecbf3f316d6e41d099e774812d470422b3a0f137ea635832"}, 548 | {file = "regex-2022.1.18-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:61ebbcd208d78658b09e19c78920f1ad38936a0aa0f9c459c46c197d11c580a0"}, 549 | {file = "regex-2022.1.18-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:b013f759cd69cb0a62de954d6d2096d648bc210034b79b1881406b07ed0a83f9"}, 550 | {file = "regex-2022.1.18-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:9187500d83fd0cef4669385cbb0961e227a41c0c9bc39219044e35810793edf7"}, 551 | {file = "regex-2022.1.18-cp310-cp310-win32.whl", hash = "sha256:94c623c331a48a5ccc7d25271399aff29729fa202c737ae3b4b28b89d2b0976d"}, 552 | {file = "regex-2022.1.18-cp310-cp310-win_amd64.whl", hash = "sha256:1a171eaac36a08964d023eeff740b18a415f79aeb212169080c170ec42dd5184"}, 553 | {file = "regex-2022.1.18-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:49810f907dfe6de8da5da7d2b238d343e6add62f01a15d03e2195afc180059ed"}, 554 | {file = "regex-2022.1.18-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0d2f5c3f7057530afd7b739ed42eb04f1011203bc5e4663e1e1d01bb50f813e3"}, 555 | {file = "regex-2022.1.18-cp36-cp36m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:85ffd6b1cb0dfb037ede50ff3bef80d9bf7fa60515d192403af6745524524f3b"}, 556 | {file = "regex-2022.1.18-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ba37f11e1d020969e8a779c06b4af866ffb6b854d7229db63c5fdddfceaa917f"}, 557 | {file = "regex-2022.1.18-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:637e27ea1ebe4a561db75a880ac659ff439dec7f55588212e71700bb1ddd5af9"}, 558 | {file = "regex-2022.1.18-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:37978254d9d00cda01acc1997513f786b6b971e57b778fbe7c20e30ae81a97f3"}, 559 | {file = "regex-2022.1.18-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:e54a1eb9fd38f2779e973d2f8958fd575b532fe26013405d1afb9ee2374e7ab8"}, 560 | {file = "regex-2022.1.18-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:768632fd8172ae03852e3245f11c8a425d95f65ff444ce46b3e673ae5b057b74"}, 561 | {file = "regex-2022.1.18-cp36-cp36m-musllinux_1_1_i686.whl", hash = "sha256:de2923886b5d3214be951bc2ce3f6b8ac0d6dfd4a0d0e2a4d2e5523d8046fdfb"}, 562 | {file = "regex-2022.1.18-cp36-cp36m-musllinux_1_1_ppc64le.whl", hash = "sha256:1333b3ce73269f986b1fa4d5d395643810074dc2de5b9d262eb258daf37dc98f"}, 563 | {file = "regex-2022.1.18-cp36-cp36m-musllinux_1_1_s390x.whl", hash = "sha256:d19a34f8a3429bd536996ad53597b805c10352a8561d8382e05830df389d2b43"}, 564 | {file = "regex-2022.1.18-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:8d2f355a951f60f0843f2368b39970e4667517e54e86b1508e76f92b44811a8a"}, 565 | {file = "regex-2022.1.18-cp36-cp36m-win32.whl", hash = "sha256:2245441445099411b528379dee83e56eadf449db924648e5feb9b747473f42e3"}, 566 | {file = "regex-2022.1.18-cp36-cp36m-win_amd64.whl", hash = "sha256:25716aa70a0d153cd844fe861d4f3315a6ccafce22b39d8aadbf7fcadff2b633"}, 567 | {file = "regex-2022.1.18-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:7e070d3aef50ac3856f2ef5ec7214798453da878bb5e5a16c16a61edf1817cc3"}, 568 | {file = "regex-2022.1.18-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:22709d701e7037e64dae2a04855021b62efd64a66c3ceed99dfd684bfef09e38"}, 569 | {file = "regex-2022.1.18-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c9099bf89078675c372339011ccfc9ec310310bf6c292b413c013eb90ffdcafc"}, 570 | {file = "regex-2022.1.18-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:04611cc0f627fc4a50bc4a9a2e6178a974c6a6a4aa9c1cca921635d2c47b9c87"}, 571 | {file = "regex-2022.1.18-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:552a39987ac6655dad4bf6f17dd2b55c7b0c6e949d933b8846d2e312ee80005a"}, 572 | {file = "regex-2022.1.18-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1e031899cb2bc92c0cf4d45389eff5b078d1936860a1be3aa8c94fa25fb46ed8"}, 573 | {file = "regex-2022.1.18-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:2dacb3dae6b8cc579637a7b72f008bff50a94cde5e36e432352f4ca57b9e54c4"}, 574 | {file = "regex-2022.1.18-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:e5c31d70a478b0ca22a9d2d76d520ae996214019d39ed7dd93af872c7f301e52"}, 575 | {file = "regex-2022.1.18-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:bb804c7d0bfbd7e3f33924ff49757de9106c44e27979e2492819c16972ec0da2"}, 576 | {file = "regex-2022.1.18-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:36b2d700a27e168fa96272b42d28c7ac3ff72030c67b32f37c05616ebd22a202"}, 577 | {file = "regex-2022.1.18-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:16f81025bb3556eccb0681d7946e2b35ff254f9f888cff7d2120e8826330315c"}, 578 | {file = "regex-2022.1.18-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:da80047524eac2acf7c04c18ac7a7da05a9136241f642dd2ed94269ef0d0a45a"}, 579 | {file = "regex-2022.1.18-cp37-cp37m-win32.whl", hash = "sha256:6ca45359d7a21644793de0e29de497ef7f1ae7268e346c4faf87b421fea364e6"}, 580 | {file = "regex-2022.1.18-cp37-cp37m-win_amd64.whl", hash = "sha256:38289f1690a7e27aacd049e420769b996826f3728756859420eeee21cc857118"}, 581 | {file = "regex-2022.1.18-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:6014038f52b4b2ac1fa41a58d439a8a00f015b5c0735a0cd4b09afe344c94899"}, 582 | {file = "regex-2022.1.18-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:0b5d6f9aed3153487252d00a18e53f19b7f52a1651bc1d0c4b5844bc286dfa52"}, 583 | {file = "regex-2022.1.18-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a9d24b03daf7415f78abc2d25a208f234e2c585e5e6f92f0204d2ab7b9ab48e3"}, 584 | {file = "regex-2022.1.18-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:bf594cc7cc9d528338d66674c10a5b25e3cde7dd75c3e96784df8f371d77a298"}, 585 | {file = "regex-2022.1.18-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:fd914db437ec25bfa410f8aa0aa2f3ba87cdfc04d9919d608d02330947afaeab"}, 586 | {file = "regex-2022.1.18-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:90b6840b6448203228a9d8464a7a0d99aa8fa9f027ef95fe230579abaf8a6ee1"}, 587 | {file = "regex-2022.1.18-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:11772be1eb1748e0e197a40ffb82fb8fd0d6914cd147d841d9703e2bef24d288"}, 588 | {file = "regex-2022.1.18-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:a602bdc8607c99eb5b391592d58c92618dcd1537fdd87df1813f03fed49957a6"}, 589 | {file = "regex-2022.1.18-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:7e26eac9e52e8ce86f915fd33380f1b6896a2b51994e40bb094841e5003429b4"}, 590 | {file = "regex-2022.1.18-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:519c0b3a6fbb68afaa0febf0d28f6c4b0a1074aefc484802ecb9709faf181607"}, 591 | {file = "regex-2022.1.18-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:3c7ea86b9ca83e30fa4d4cd0eaf01db3ebcc7b2726a25990966627e39577d729"}, 592 | {file = "regex-2022.1.18-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:51f02ca184518702975b56affde6c573ebad4e411599005ce4468b1014b4786c"}, 593 | {file = "regex-2022.1.18-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:385ccf6d011b97768a640e9d4de25412204fbe8d6b9ae39ff115d4ff03f6fe5d"}, 594 | {file = "regex-2022.1.18-cp38-cp38-win32.whl", hash = "sha256:1f8c0ae0a0de4e19fddaaff036f508db175f6f03db318c80bbc239a1def62d02"}, 595 | {file = "regex-2022.1.18-cp38-cp38-win_amd64.whl", hash = "sha256:760c54ad1b8a9b81951030a7e8e7c3ec0964c1cb9fee585a03ff53d9e531bb8e"}, 596 | {file = "regex-2022.1.18-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:93c20777a72cae8620203ac11c4010365706062aa13aaedd1a21bb07adbb9d5d"}, 597 | {file = "regex-2022.1.18-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:6aa427c55a0abec450bca10b64446331b5ca8f79b648531138f357569705bc4a"}, 598 | {file = "regex-2022.1.18-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c38baee6bdb7fe1b110b6b3aaa555e6e872d322206b7245aa39572d3fc991ee4"}, 599 | {file = "regex-2022.1.18-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:752e7ddfb743344d447367baa85bccd3629c2c3940f70506eb5f01abce98ee68"}, 600 | {file = "regex-2022.1.18-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8acef4d8a4353f6678fd1035422a937c2170de58a2b29f7da045d5249e934101"}, 601 | {file = "regex-2022.1.18-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c73d2166e4b210b73d1429c4f1ca97cea9cc090e5302df2a7a0a96ce55373f1c"}, 602 | {file = "regex-2022.1.18-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:24c89346734a4e4d60ecf9b27cac4c1fee3431a413f7aa00be7c4d7bbacc2c4d"}, 603 | {file = "regex-2022.1.18-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:596f5ae2eeddb79b595583c2e0285312b2783b0ec759930c272dbf02f851ff75"}, 604 | {file = "regex-2022.1.18-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:ecfe51abf7f045e0b9cdde71ca9e153d11238679ef7b5da6c82093874adf3338"}, 605 | {file = "regex-2022.1.18-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:1d6301f5288e9bdca65fab3de6b7de17362c5016d6bf8ee4ba4cbe833b2eda0f"}, 606 | {file = "regex-2022.1.18-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:93cce7d422a0093cfb3606beae38a8e47a25232eea0f292c878af580a9dc7605"}, 607 | {file = "regex-2022.1.18-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:cf0db26a1f76aa6b3aa314a74b8facd586b7a5457d05b64f8082a62c9c49582a"}, 608 | {file = "regex-2022.1.18-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:defa0652696ff0ba48c8aff5a1fac1eef1ca6ac9c660b047fc8e7623c4eb5093"}, 609 | {file = "regex-2022.1.18-cp39-cp39-win32.whl", hash = "sha256:6db1b52c6f2c04fafc8da17ea506608e6be7086715dab498570c3e55e4f8fbd1"}, 610 | {file = "regex-2022.1.18-cp39-cp39-win_amd64.whl", hash = "sha256:ebaeb93f90c0903233b11ce913a7cb8f6ee069158406e056f884854c737d2442"}, 611 | {file = "regex-2022.1.18.tar.gz", hash = "sha256:97f32dc03a8054a4c4a5ab5d761ed4861e828b2c200febd4e46857069a483916"}, 612 | ] 613 | setuptools = [ 614 | {file = "setuptools-65.6.0-py3-none-any.whl", hash = "sha256:6211d2f5eddad8757bd0484923ca7c0a6302ebc4ab32ea5e94357176e0ca0840"}, 615 | {file = "setuptools-65.6.0.tar.gz", hash = "sha256:d1eebf881c6114e51df1664bc2c9133d022f78d12d5f4f665b9191f084e2862d"}, 616 | ] 617 | setuptools-scm = [ 618 | {file = "setuptools_scm-6.4.2-py3-none-any.whl", hash = "sha256:acea13255093849de7ccb11af9e1fb8bde7067783450cee9ef7a93139bddf6d4"}, 619 | {file = "setuptools_scm-6.4.2.tar.gz", hash = "sha256:6833ac65c6ed9711a4d5d2266f8024cfa07c533a0e55f4c12f6eff280a5a9e30"}, 620 | ] 621 | six = [ 622 | {file = "six-1.16.0-py2.py3-none-any.whl", hash = "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254"}, 623 | {file = "six-1.16.0.tar.gz", hash = "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926"}, 624 | ] 625 | toml = [ 626 | {file = "toml-0.10.2-py2.py3-none-any.whl", hash = "sha256:806143ae5bfb6a3c6e736a764057db0e6a0e05e338b5630894a5f779cabb4f9b"}, 627 | {file = "toml-0.10.2.tar.gz", hash = "sha256:b3bda1d108d5dd99f4a20d24d9c348e91c4db7ab1b749200bded2f839ccbe68f"}, 628 | ] 629 | tomli = [ 630 | {file = "tomli-2.0.0-py3-none-any.whl", hash = "sha256:b5bde28da1fed24b9bd1d4d2b8cba62300bfb4ec9a6187a957e8ddb9434c5224"}, 631 | {file = "tomli-2.0.0.tar.gz", hash = "sha256:c292c34f58502a1eb2bbb9f5bbc9a5ebc37bee10ffb8c2d6bbdfa8eb13cc14e1"}, 632 | ] 633 | typed-ast = [ 634 | {file = "typed_ast-1.5.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:183b183b7771a508395d2cbffd6db67d6ad52958a5fdc99f450d954003900266"}, 635 | {file = "typed_ast-1.5.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:676d051b1da67a852c0447621fdd11c4e104827417bf216092ec3e286f7da596"}, 636 | {file = "typed_ast-1.5.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bc2542e83ac8399752bc16e0b35e038bdb659ba237f4222616b4e83fb9654985"}, 637 | {file = "typed_ast-1.5.2-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:74cac86cc586db8dfda0ce65d8bcd2bf17b58668dfcc3652762f3ef0e6677e76"}, 638 | {file = "typed_ast-1.5.2-cp310-cp310-win_amd64.whl", hash = "sha256:18fe320f354d6f9ad3147859b6e16649a0781425268c4dde596093177660e71a"}, 639 | {file = "typed_ast-1.5.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:31d8c6b2df19a777bc8826770b872a45a1f30cfefcfd729491baa5237faae837"}, 640 | {file = "typed_ast-1.5.2-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:963a0ccc9a4188524e6e6d39b12c9ca24cc2d45a71cfdd04a26d883c922b4b78"}, 641 | {file = "typed_ast-1.5.2-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:0eb77764ea470f14fcbb89d51bc6bbf5e7623446ac4ed06cbd9ca9495b62e36e"}, 642 | {file = "typed_ast-1.5.2-cp36-cp36m-win_amd64.whl", hash = "sha256:294a6903a4d087db805a7656989f613371915fc45c8cc0ddc5c5a0a8ad9bea4d"}, 643 | {file = "typed_ast-1.5.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:26a432dc219c6b6f38be20a958cbe1abffcc5492821d7e27f08606ef99e0dffd"}, 644 | {file = "typed_ast-1.5.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c7407cfcad702f0b6c0e0f3e7ab876cd1d2c13b14ce770e412c0c4b9728a0f88"}, 645 | {file = "typed_ast-1.5.2-cp37-cp37m-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:f30ddd110634c2d7534b2d4e0e22967e88366b0d356b24de87419cc4410c41b7"}, 646 | {file = "typed_ast-1.5.2-cp37-cp37m-win_amd64.whl", hash = "sha256:8c08d6625bb258179b6e512f55ad20f9dfef019bbfbe3095247401e053a3ea30"}, 647 | {file = "typed_ast-1.5.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:90904d889ab8e81a956f2c0935a523cc4e077c7847a836abee832f868d5c26a4"}, 648 | {file = "typed_ast-1.5.2-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:bbebc31bf11762b63bf61aaae232becb41c5bf6b3461b80a4df7e791fabb3aca"}, 649 | {file = "typed_ast-1.5.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c29dd9a3a9d259c9fa19d19738d021632d673f6ed9b35a739f48e5f807f264fb"}, 650 | {file = "typed_ast-1.5.2-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:58ae097a325e9bb7a684572d20eb3e1809802c5c9ec7108e85da1eb6c1a3331b"}, 651 | {file = "typed_ast-1.5.2-cp38-cp38-win_amd64.whl", hash = "sha256:da0a98d458010bf4fe535f2d1e367a2e2060e105978873c04c04212fb20543f7"}, 652 | {file = "typed_ast-1.5.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:33b4a19ddc9fc551ebabca9765d54d04600c4a50eda13893dadf67ed81d9a098"}, 653 | {file = "typed_ast-1.5.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:1098df9a0592dd4c8c0ccfc2e98931278a6c6c53cb3a3e2cf7e9ee3b06153344"}, 654 | {file = "typed_ast-1.5.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:42c47c3b43fe3a39ddf8de1d40dbbfca60ac8530a36c9b198ea5b9efac75c09e"}, 655 | {file = "typed_ast-1.5.2-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:f290617f74a610849bd8f5514e34ae3d09eafd521dceaa6cf68b3f4414266d4e"}, 656 | {file = "typed_ast-1.5.2-cp39-cp39-win_amd64.whl", hash = "sha256:df05aa5b241e2e8045f5f4367a9f6187b09c4cdf8578bb219861c4e27c443db5"}, 657 | {file = "typed_ast-1.5.2.tar.gz", hash = "sha256:525a2d4088e70a9f75b08b3f87a51acc9cde640e19cc523c7e41aa355564ae27"}, 658 | ] 659 | -------------------------------------------------------------------------------- /tools/pyproject.toml: -------------------------------------------------------------------------------- 1 | [tool.poetry] 2 | name = "temp_plotter" 3 | version = "0.1.0" 4 | description = "Temperature plotter" 5 | authors = ["Alberto Cardellini"] 6 | 7 | [tool.poetry.dependencies] 8 | python = "^3.8" 9 | pyserial = "^3.4" 10 | matplotlib = "^3.2.1" 11 | 12 | [tool.poetry.dev-dependencies] 13 | flake8 = "^3.8.3" 14 | black = {version = "^19.10b0", allow-prereleases = true} 15 | 16 | [tool.black] 17 | line-length = 88 18 | include = '\.pyi?$' 19 | exclude = ''' 20 | /( 21 | \.git 22 | | \.hg 23 | | \.mypy_cache 24 | | \.tox 25 | | \.venv 26 | | _build 27 | | buck-out 28 | | build 29 | | dist 30 | )/ 31 | ''' 32 | 33 | [build-system] 34 | requires = ["poetry>=0.12"] 35 | build-backend = "poetry.masonry.api" -------------------------------------------------------------------------------- /tools/temp_plotter.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | from threading import Thread 4 | import serial 5 | import time 6 | import matplotlib.pyplot as plt 7 | import matplotlib.animation as animation 8 | import copy 9 | import argparse 10 | 11 | 12 | class SerialPlotter: 13 | def __init__(self, port, baudrate, plot_size=1000): 14 | print("Starting serial connection...") 15 | self.plot_size = plot_size 16 | # Serial connection 17 | self.connection = serial.Serial(port, baudrate) 18 | # Read serial data in the background 19 | self.data_reader = Thread(target=self.read_serial_data) 20 | # Notify input data started 21 | self.receiving_data = False 22 | # Flag to stop the endless background thread 23 | self.active = True 24 | # Serial raw bytes 25 | self.raw_data = bytes() 26 | # List to store data to plot 27 | self.data = { 28 | "current": [0 for i in range(self.plot_size)], 29 | "target": [0 for i in range(self.plot_size)], 30 | "ssr": [0 for i in range(self.plot_size)], 31 | } 32 | self.previous_plot_timer = 0 33 | 34 | def start(self): 35 | print("Reading serial data...") 36 | # self.send("output on") 37 | self.data_reader.start() 38 | while not self.receiving_data: 39 | time.sleep(0.1) 40 | self.setup_plot() 41 | plt.show() 42 | 43 | def stop(self): 44 | print("Disconnecting serial connection...") 45 | # self.send("output off") 46 | self.active = False 47 | self.data_reader.join() 48 | self.connection.close() 49 | 50 | def setup_plot(self): 51 | fig = plt.figure(figsize=(10, 8)) 52 | ax = plt.axes(xlim=(0.0, self.plot_size), ylim=(0.0, 200.0)) 53 | ax.set_title("Temperature Plotter") 54 | ax.set_xlabel("Time") 55 | ax.set_ylabel("Temperature C") 56 | 57 | line_labels = ["CurrentT", "TargetT", "SSR"] 58 | styles = ["r-", "c-", "b-"] 59 | x_ax_text = ax.text(0.70, 0.95, "", transform=ax.transAxes) 60 | lines = [] 61 | lines_text = [] 62 | for i in range(len(self.data)): 63 | lines.append(ax.plot([], [], styles[i], label=line_labels[i])[0]) 64 | lines_text.append( 65 | ax.text(0.70, 0.90 - i * 0.05, "", transform=ax.transAxes) 66 | ) 67 | self.anim = animation.FuncAnimation( 68 | fig, 69 | self.decode_and_plot_data, 70 | fargs=(lines, lines_text, line_labels, x_ax_text), 71 | interval=50, 72 | ) 73 | plt.legend(loc="upper left") 74 | 75 | def read_serial_data(self): 76 | time.sleep(1) 77 | self.connection.reset_input_buffer() 78 | while self.active: 79 | self.raw_data = self.connection.readline() 80 | self.receiving_data = True 81 | 82 | def decode_and_plot_data(self, frame, lines, lines_text, line_labels, x_ax_text): 83 | currentTimer = time.perf_counter() 84 | self.plot_timer = int((currentTimer - self.previous_plot_timer) * 1000) 85 | self.previous_plot_timer = currentTimer 86 | x_ax_text.set_text("Plot Interval = " + str(self.plot_timer) + "ms") 87 | # Update the plot only if new data was received 88 | if len(self.raw_data) < 1: 89 | return 90 | # Decode raw data 91 | string_data = copy.deepcopy(self.raw_data[:]).decode("utf-8").split(",") 92 | # Add decoded data into plot datastores 93 | if len(string_data) < 3: 94 | return 95 | self.data["current"].append(float(string_data[1])) 96 | self.data["target"].append(float(string_data[2])) 97 | self.data["ssr"].append(int(string_data[3]) * 10) 98 | # Update plot with decoded data 99 | lines[0].set_data( 100 | range(self.plot_size), self.data["current"][-self.plot_size :] 101 | ) 102 | lines_text[0].set_text("[" + line_labels[0] + "] = " + str(string_data[1])) 103 | lines[1].set_data(range(self.plot_size), self.data["target"][-self.plot_size :]) 104 | lines_text[1].set_text("[" + line_labels[1] + "] = " + str(string_data[2])) 105 | lines[2].set_data(range(self.plot_size), self.data["ssr"][-self.plot_size :]) 106 | lines_text[2].set_text("[" + line_labels[2] + "] = " + str(string_data[3])) 107 | # Reset raw data 108 | self.raw_data = bytes() 109 | 110 | def send(self, string): 111 | print("Sending: {}".format(string)) 112 | self.connection.write(bytes(string.encode("utf-8"))) 113 | 114 | 115 | def main(): 116 | parser = argparse.ArgumentParser(prog="Temperature Serial Plotter") 117 | parser.add_argument( 118 | "-d", 119 | "--device", 120 | help="The full path of the serial device to use", 121 | default="/dev/ttyUSB0", 122 | metavar="DEVICE", 123 | type=str, 124 | ) 125 | parser.add_argument( 126 | "-b", 127 | "--baudrate", 128 | help="The baudrate used to communicate with the serial device", 129 | default=9600, 130 | metavar="BAUDRATE", 131 | type=int, 132 | ) 133 | args = parser.parse_args() 134 | try: 135 | plotter = SerialPlotter(port=args.device, baudrate=args.baudrate) 136 | plotter.start() 137 | except serial.serialutil.SerialException as e: 138 | print(e) 139 | exit(1) 140 | except Exception as e: 141 | print(e) 142 | print("Exiting...") 143 | plotter.stop() 144 | 145 | 146 | if __name__ == "__main__": 147 | main() 148 | --------------------------------------------------------------------------------