Skip to content
Snippets Groups Projects
Commit 66f44831 authored by David Gauchard's avatar David Gauchard
Browse files

consolidate

parent 35a4a31a
No related branches found
No related tags found
1 merge request!17Malaurie's work on UI + CLI interface + AccelStepper interface
...@@ -190,7 +190,7 @@ void Cli::loop (Stream& input) ...@@ -190,7 +190,7 @@ void Cli::loop (Stream& input)
copyNextToTemp(); 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"))) else if (kw(F("MM")))
{ {
...@@ -203,7 +203,7 @@ void Cli::loop (Stream& input) ...@@ -203,7 +203,7 @@ void Cli::loop (Stream& input)
copyNextToTemp(); 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"))) else if (kw(F("DIA")))
{ {
......
...@@ -66,12 +66,15 @@ public: ...@@ -66,12 +66,15 @@ public:
#if CORE_MOCK #if CORE_MOCK
return 0; return 0;
#else #else
return stepper.currentPosition(); return stepper.currentPosition() * (_forwardClockwise? 1: -1);
#endif #endif
} }
void moveToMm (float mm) void moveToMm (float mm)
{ {
Serial.printf("# moving to %g mm / %g steps\n",
mm,
mmToStep(mm));
moveToStep(mmToStep(mm)); moveToStep(mmToStep(mm));
} }
...@@ -122,14 +125,11 @@ public: ...@@ -122,14 +125,11 @@ public:
Serial.printf("# %g mm/rev\n" Serial.printf("# %g mm/rev\n"
"# %d steps/rev\n" "# %d steps/rev\n"
"# %g steps/mm\n" "# %g steps/mm\n"
"# position: %ld steps / %g mm\n"
"# max speed: %g steps/s %g mm/s\n" "# max speed: %g steps/s %g mm/s\n"
"# accel: %g steps/s/s %g mm/s/s\n", "# accel: %g steps/s/s %g mm/s/s\n",
_mmPerRevolution, _mmPerRevolution,
_stepsPerRevolution, _stepsPerRevolution,
_stepsPerRevolution / _mmPerRevolution, _stepsPerRevolution / _mmPerRevolution,
stepper.currentPosition(),
stepToMm(stepper.currentPosition()),
stepper.maxSpeed(), stepper.maxSpeed(),
stepToMm(stepper.maxSpeed()), stepToMm(stepper.maxSpeed()),
stepper.acceleration(), stepper.acceleration(),
......
...@@ -7,8 +7,12 @@ ...@@ -7,8 +7,12 @@
#undef STAPSK #undef STAPSK
#ifndef STASSID #ifndef STASSID
#define STASSID "" #define STASSID "laas-capture"
#define STAPSK "WifiLAAS2022" // this password is wrong #define STAPSK ""
#endif
#ifndef ARDUINO_ESP8266_ADAFRUIT_HUZZAH
#error select board Adafruit Feather HUZZAH ESP8266
#endif #endif
#define NAME "PousseSeringue" #define NAME "PousseSeringue"
...@@ -284,13 +288,16 @@ void setup() ...@@ -284,13 +288,16 @@ void setup()
uint8_t mac[6]; uint8_t mac[6];
WiFi.macAddress(mac); WiFi.macAddress(mac);
sprintf(ssid, NAME "-%02x%02x%02x", mac[3], mac[4], mac[5]); sprintf(ssid, NAME "-%02x%02x%02x", mac[3], mac[4], mac[5]);
#if 0
if (strlen(STASSID) > 0) if (strlen(STASSID) > 0)
{ {
WiFi.mode(WIFI_AP_STA); WiFi.setPhyMode(WIFI_PHY_MODE_11G);
WiFi.softAP(ssid); WiFi.mode(WIFI_STA);
WiFi.begin(STASSID, STAPSK); //WiFi.softAP(ssid);
WiFi.hostname(ssid); WiFi.hostname(ssid);
WiFi.begin(STASSID, STAPSK);
} }
#endif
// redirect everything to my AP ip: // redirect everything to my AP ip:
dnsServer.setErrorReplyCode(DNSReplyCode::NoError); dnsServer.setErrorReplyCode(DNSReplyCode::NoError);
...@@ -375,6 +382,6 @@ void loop() ...@@ -375,6 +382,6 @@ void loop()
} }
console.loop(Serial); console.loop(Serial);
webLoop(); //webLoop();
dnsServer.processNextRequest(); // access-point redirection //dnsServer.processNextRequest(); // access-point redirection
} }
...@@ -5,13 +5,17 @@ ...@@ -5,13 +5,17 @@
void Syringe::showConfiguration (const Syringe_configuration_t& conf) void Syringe::showConfiguration (const Syringe_configuration_t& conf)
{ {
Motor::showConfiguration(); Motor::showConfiguration();
auto step = whereStep();
Serial.printf("# diameter: %g mm\n" Serial.printf("# diameter: %g mm\n"
"# capacity: %g uL\n" "# capacity: %g uL\n"
"# rate: %g uL/s = %g mm/s\n" "# rate: %g uL/s = %g mm/s\n"
"# volume: %g uL\n" "# volume: %g uL (target)\n"
"# direction: %s\n" "# direction: %s\n"
"# zeroing: %d\n" "# zeroing: %d\n"
"# emergency: %d\n", "# emergency: %d\n"
"# current position: %g mm %g ul %d steps\n",
conf.diameter_mm, conf.diameter_mm,
conf.capacity_ul, conf.capacity_ul,
conf.rate_ul_per_s, conf.rate_ul_per_s,
...@@ -19,7 +23,8 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf) ...@@ -19,7 +23,8 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf)
conf.volume_value * conf.volume_unit_ul, conf.volume_value * conf.volume_unit_ul,
conf.direction > 0? "infuse": "withdraw", conf.direction > 0? "infuse": "withdraw",
conf.findZero, conf.findZero,
emergency()); emergency(),
stepToMm(step), mmToMm3(stepToMm(step)), step);
} }
float Syringe::confToMm3 () const float Syringe::confToMm3 () const
...@@ -27,14 +32,19 @@ 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; 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 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 float Syringe::mmToMm3 (float mm) const
{ {
return mm * (pow(current_configuration.diameter_mm / 2, 2) * M_PI); return mm * sectionMm2();
} }
float Syringe::confToMm () const float Syringe::confToMm () const
...@@ -126,7 +136,7 @@ void Syringe::manageEmergency (bool pressed, bool stepperMoving) ...@@ -126,7 +136,7 @@ void Syringe::manageEmergency (bool pressed, bool stepperMoving)
current_configuration.findZero = false; current_configuration.findZero = false;
setEmergency(false); setEmergency(false);
resetPosition(); resetPosition();
Serial.printf("EMERGENCY: danger faded away\n"); Serial.printf("ZERO: reset\n");
} }
else else
{ {
......
...@@ -59,6 +59,7 @@ public: ...@@ -59,6 +59,7 @@ public:
float mmToMm3 (float mm) const; float mmToMm3 (float mm) const;
float confToMm () const; float confToMm () const;
float confToMm3 () const; float confToMm3 () const;
float sectionMm2 () const;
// Actions // Actions
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment