From 66f44831377d3f504367816f08164dd91d601dda Mon Sep 17 00:00:00 2001 From: David Gauchard <gauchard@laas.fr> Date: Tue, 25 Apr 2023 18:29:57 +0200 Subject: [PATCH] consolidate --- cli.cpp | 4 ++-- motor.h | 8 ++++---- pousseseringue-arduino.cpp | 21 ++++++++++++++------- syringe.cpp | 22 ++++++++++++++++------ syringe.h | 1 + 5 files changed, 37 insertions(+), 19 deletions(-) diff --git a/cli.cpp b/cli.cpp index 61f184c..968e3c8 100644 --- a/cli.cpp +++ b/cli.cpp @@ -190,7 +190,7 @@ void Cli::loop (Stream& input) copyNextToTemp(); } - Serial.printf("%sVOL: %g ul (%g mm)\n", _msgHeader.c_str(), syringe.confToMm3(), syringe.confToMm()); + Serial.printf("%sVOL: %g ul (%g mm) (target)\n", _msgHeader.c_str(), syringe.confToMm3(), syringe.confToMm()); } else if (kw(F("MM"))) { @@ -203,7 +203,7 @@ void Cli::loop (Stream& input) copyNextToTemp(); } - Serial.printf("%sVOL: %g ul (%g mm)\n", _msgHeader.c_str(), syringe.confToMm3(), syringe.confToMm()); + Serial.printf("%sVOL: %g ul (%g mm) (target)\n", _msgHeader.c_str(), syringe.confToMm3(), syringe.confToMm()); } else if (kw(F("DIA"))) { diff --git a/motor.h b/motor.h index 51ba067..755db7e 100644 --- a/motor.h +++ b/motor.h @@ -66,12 +66,15 @@ public: #if CORE_MOCK return 0; #else - return stepper.currentPosition(); + return stepper.currentPosition() * (_forwardClockwise? 1: -1); #endif } void moveToMm (float mm) { + Serial.printf("# moving to %g mm / %g steps\n", + mm, + mmToStep(mm)); moveToStep(mmToStep(mm)); } @@ -122,14 +125,11 @@ public: Serial.printf("# %g mm/rev\n" "# %d steps/rev\n" "# %g steps/mm\n" - "# position: %ld steps / %g mm\n" "# max speed: %g steps/s %g mm/s\n" "# accel: %g steps/s/s %g mm/s/s\n", _mmPerRevolution, _stepsPerRevolution, _stepsPerRevolution / _mmPerRevolution, - stepper.currentPosition(), - stepToMm(stepper.currentPosition()), stepper.maxSpeed(), stepToMm(stepper.maxSpeed()), stepper.acceleration(), diff --git a/pousseseringue-arduino.cpp b/pousseseringue-arduino.cpp index 05cef8d..80e72ba 100644 --- a/pousseseringue-arduino.cpp +++ b/pousseseringue-arduino.cpp @@ -7,8 +7,12 @@ #undef STAPSK #ifndef STASSID -#define STASSID "" -#define STAPSK "WifiLAAS2022" // this password is wrong +#define STASSID "laas-capture" +#define STAPSK "" +#endif + +#ifndef ARDUINO_ESP8266_ADAFRUIT_HUZZAH +#error select board Adafruit Feather HUZZAH ESP8266 #endif #define NAME "PousseSeringue" @@ -284,13 +288,16 @@ void setup() uint8_t mac[6]; WiFi.macAddress(mac); sprintf(ssid, NAME "-%02x%02x%02x", mac[3], mac[4], mac[5]); +#if 0 if (strlen(STASSID) > 0) { - WiFi.mode(WIFI_AP_STA); - WiFi.softAP(ssid); - WiFi.begin(STASSID, STAPSK); + WiFi.setPhyMode(WIFI_PHY_MODE_11G); + WiFi.mode(WIFI_STA); + //WiFi.softAP(ssid); WiFi.hostname(ssid); + WiFi.begin(STASSID, STAPSK); } +#endif // redirect everything to my AP ip: dnsServer.setErrorReplyCode(DNSReplyCode::NoError); @@ -375,6 +382,6 @@ void loop() } console.loop(Serial); - webLoop(); - dnsServer.processNextRequest(); // access-point redirection + //webLoop(); + //dnsServer.processNextRequest(); // access-point redirection } diff --git a/syringe.cpp b/syringe.cpp index b681e47..00993f4 100644 --- a/syringe.cpp +++ b/syringe.cpp @@ -5,13 +5,17 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf) { Motor::showConfiguration(); + + auto step = whereStep(); + Serial.printf("# diameter: %g mm\n" "# capacity: %g uL\n" "# rate: %g uL/s = %g mm/s\n" - "# volume: %g uL\n" + "# volume: %g uL (target)\n" "# direction: %s\n" "# zeroing: %d\n" - "# emergency: %d\n", + "# emergency: %d\n" + "# current position: %g mm %g ul %d steps\n", conf.diameter_mm, conf.capacity_ul, conf.rate_ul_per_s, @@ -19,7 +23,8 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf) conf.volume_value * conf.volume_unit_ul, conf.direction > 0? "infuse": "withdraw", conf.findZero, - emergency()); + emergency(), + stepToMm(step), mmToMm3(stepToMm(step)), step); } float Syringe::confToMm3 () const @@ -27,14 +32,19 @@ float Syringe::confToMm3 () const return current_configuration.direction * current_configuration.volume_value * current_configuration.volume_unit_ul; } +float Syringe::sectionMm2 () const +{ + return pow(current_configuration.diameter_mm / 2, 2) * M_PI; +} + float Syringe::mm3ToMm (float mm3) const { - return mm3 / (pow(current_configuration.diameter_mm / 2, 2) * M_PI); + return mm3 / sectionMm2(); } float Syringe::mmToMm3 (float mm) const { - return mm * (pow(current_configuration.diameter_mm / 2, 2) * M_PI); + return mm * sectionMm2(); } float Syringe::confToMm () const @@ -126,7 +136,7 @@ void Syringe::manageEmergency (bool pressed, bool stepperMoving) current_configuration.findZero = false; setEmergency(false); resetPosition(); - Serial.printf("EMERGENCY: danger faded away\n"); + Serial.printf("ZERO: reset\n"); } else { diff --git a/syringe.h b/syringe.h index b39c03c..ce31982 100644 --- a/syringe.h +++ b/syringe.h @@ -59,6 +59,7 @@ public: float mmToMm3 (float mm) const; float confToMm () const; float confToMm3 () const; + float sectionMm2 () const; // Actions -- GitLab