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

+FS

parent b0eb6a0a
No related branches found
No related tags found
1 merge request!17Malaurie's work on UI + CLI interface + AccelStepper interface
#include "cli.h" #include "cli.h"
#include "fs.h"
void Cli::resetNextWord () void Cli::resetNextWord ()
{ {
_currentWordIndex = -1; _currentWordIndex = -1;
...@@ -74,27 +76,30 @@ void Cli::syntax (const __FlashStringHelper* cmd) ...@@ -74,27 +76,30 @@ void Cli::syntax (const __FlashStringHelper* cmd)
void Cli::syntax (const char* cmd) void Cli::syntax (const char* cmd)
{ {
if (!cmd || kw(F("AT"), cmd)) Serial.printf("%sAT -> OK\n", _msgHeader.c_str()); if (!cmd || kw(F("AT"), cmd)) Serial.printf("%sAT -> OK\n", _msgHeader);
if (!cmd || kw(F("HELP"), cmd)) Serial.printf("%sHELP [CMD]\n", _msgHeader.c_str()); if (!cmd || kw(F("HELP"), cmd)) Serial.printf("%sHELP [CMD]\n", _msgHeader);
if (!cmd || kw(F("RAT"), cmd)) Serial.printf("%sRAT [ C <rate> [<unit>] ] - set or show rate ([UM]/MM/UH/MH)\n", _msgHeader.c_str()); if (!cmd || kw(F("RAT"), cmd)) Serial.printf("%sRAT [ C <rate> [<unit>] ] - set or show rate ([UM]/MM/UH/MH)\n", _msgHeader);
if (!cmd || kw(F("VOL"), cmd)) Serial.printf("%sVOL [ <vol> | <unit> ] - set volume or unit (UL / ML)\n", _msgHeader.c_str()); if (!cmd || kw(F("VOL"), cmd)) Serial.printf("%sVOL [ <vol> | <unit> ] - set volume or unit (UL / ML)\n", _msgHeader);
if (!cmd || kw(F("MM"), cmd)) Serial.printf("%sMM [ <len> ] - set distance (mm)\n", _msgHeader.c_str()); if (!cmd || kw(F("RVOL"), cmd)) Serial.printf("%sRVOL <vol> - set relative volume\n", _msgHeader);
if (!cmd || kw(F("DIA"), cmd)) Serial.printf("%sDIA [ <dia> ] - set or show inside syringe diameter (in mm)\n", _msgHeader.c_str()); if (!cmd || kw(F("MM"), cmd)) Serial.printf("%sMM [ <len> ] - set distance (mm)\n", _msgHeader);
if (!cmd || kw(F("ACC"), cmd)) Serial.printf("%sACC [ <mm/s/s> ] - set or show acceletaration (mm/s/s) (0<=>oo)\n", _msgHeader.c_str()); if (!cmd || kw(F("RMM"), cmd)) Serial.printf("%sRMM <len> - set relative distance (mm)\n", _msgHeader);
if (!cmd || kw(F("RVM"), cmd)) Serial.printf("%sRVM [ <M4|M5> ] - set or show auger size\n", _msgHeader.c_str()); if (!cmd || kw(F("DIA"), cmd)) Serial.printf("%sDIA [ <dia> ] - set or show inside syringe diameter (in mm)\n", _msgHeader);
if (!cmd || kw(F("DIR"), cmd)) Serial.printf("%sDIR [ INF | WDR ] - set or show direction (INFuse / WithDRaw)\n", _msgHeader.c_str()); if (!cmd || kw(F("ACC"), cmd)) Serial.printf("%sACC [ <mm/s/s> ] - set or show acceletaration (mm/s/s) (0<=>oo)\n", _msgHeader);
if (!cmd || kw(F("FIL"), cmd)) Serial.printf("%sFIL - start filling using direction at rate for volume\n", _msgHeader.c_str()); if (!cmd || kw(F("RVM"), cmd)) Serial.printf("%sRVM [ <M4|M5> ] - set or show auger size\n", _msgHeader);
if (!cmd || kw(F("STP"), cmd)) Serial.printf("%sSTP - stop\n", _msgHeader.c_str()); if (!cmd || kw(F("DIR"), cmd)) Serial.printf("%sDIR [ INF | WDR ] - set or show direction (INFuse / WithDRaw)\n", _msgHeader);
if (!cmd || kw(F("DIS"), cmd)) Serial.printf("%sDIS - show volume dispensed\n", _msgHeader.c_str()); if (!cmd || kw(F("FIL"), cmd)) Serial.printf("%sFIL - start filling using direction at rate for volume\n", _msgHeader);
if (!cmd || kw(F("ZERO"), cmd)) Serial.printf("%sZERO - go to stopper\n", _msgHeader.c_str()); if (!cmd || kw(F("STP"), cmd)) Serial.printf("%sSTP - stop\n", _msgHeader);
if (!cmd || kw(F("SET0"), cmd)) Serial.printf("%sSET0 - change ZERO to current position\n", _msgHeader.c_str()); if (!cmd || kw(F("DIS"), cmd)) Serial.printf("%sDIS - show volume dispensed\n", _msgHeader);
if (!cmd || kw(F("NLCK"), cmd)) Serial.printf("%sNLCK - try to get out from stopper\n", _msgHeader.c_str()); if (!cmd || kw(F("ZERO"), cmd)) Serial.printf("%sZERO - go to stopper\n", _msgHeader);
if (!cmd || kw(F("CONF"), cmd)) Serial.printf("%sCONF - show configuration\n", _msgHeader.c_str()); if (!cmd || kw(F("SET0"), cmd)) Serial.printf("%sSET0 - change ZERO to current position\n", _msgHeader);
if (!cmd || kw(F("NLCK"), cmd)) Serial.printf("%sNLCK - try to get out from stopper\n", _msgHeader);
if (!cmd || kw(F("CLKW"), cmd)) Serial.printf("%sCLKW [0 | 1] - 1: push = rotate clockwise\n", _msgHeader);
if (!cmd || kw(F("CONF"), cmd)) Serial.printf("%sCONF - show configuration\n", _msgHeader);
} }
void Cli::answer (bool ok, const String& error_message) const void Cli::answer (bool ok, const String& error_message) const
{ {
Serial.printf("%s%s", _msgHeader.c_str(), ok? "OK": "ERROR"); Serial.printf("%s%s", _msgHeader, ok? "OK": "ERROR");
if (!ok && error_message.length()) if (!ok && error_message.length())
Serial.printf(" (%s)", error_message.c_str()); Serial.printf(" (%s)", error_message.c_str());
Serial.printf("\n"); Serial.printf("\n");
...@@ -103,7 +108,7 @@ void Cli::answer (bool ok, const String& error_message) const ...@@ -103,7 +108,7 @@ void Cli::answer (bool ok, const String& error_message) const
void Cli::checkEmergency () void Cli::checkEmergency ()
{ {
if (syringe.emergency()) if (syringe.emergency())
Serial.printf("%sin EMERGENCY state, try NLCK command\n", _msgHeader.c_str()); Serial.printf("%sin EMERGENCY state, try NLCK command\n", _msgHeader);
} }
void Cli::loop (Stream& input) void Cli::loop (Stream& input)
...@@ -167,7 +172,7 @@ void Cli::loop (Stream& input) ...@@ -167,7 +172,7 @@ void Cli::loop (Stream& input)
else if (_temp.length() > 0) else if (_temp.length() > 0)
answer(false, F("RAT must be followed by C")); answer(false, F("RAT must be followed by C"));
Serial.printf("%sRAT: %g ul/mn\n", _msgHeader.c_str(), Serial.printf("%sRAT: %g ul/mn\n", _msgHeader,
syringe.configuration().rate_ul_per_s * 60); syringe.configuration().rate_ul_per_s * 60);
} }
...@@ -192,7 +197,20 @@ void Cli::loop (Stream& input) ...@@ -192,7 +197,20 @@ void Cli::loop (Stream& input)
copyNextToTemp(); copyNextToTemp();
} }
Serial.printf("%sVOL: %g ul (%g mm) (target)\n", _msgHeader.c_str(), syringe.confToMm3(), syringe.confToMm()); Serial.printf("%sVOL: %g ul (%g mm) (target)\n", _msgHeader, syringe.confToMm3(), syringe.confToMm());
}
else if (kw(F("RVOL")))
{
copyNextToTemp();
while (_temp.length())
{
if (isdigit(_temp[0]) || _temp[0] == '-')
conf.volume_value += atof(_temp.c_str());
answer(syringe.configureSyringe(conf), F("invalid relative volume"));
copyNextToTemp();
}
Serial.printf("%sRVOL: %g ul (%g mm) (target)\n", _msgHeader, syringe.confToMm3(), syringe.confToMm());
} }
else if (kw(F("MM"))) else if (kw(F("MM")))
{ {
...@@ -205,7 +223,20 @@ void Cli::loop (Stream& input) ...@@ -205,7 +223,20 @@ void Cli::loop (Stream& input)
copyNextToTemp(); copyNextToTemp();
} }
Serial.printf("%sVOL: %g ul (%g mm) (target)\n", _msgHeader.c_str(), syringe.confToMm3(), syringe.confToMm()); Serial.printf("%sMM: %g ul (%g mm) (target)\n", _msgHeader, syringe.confToMm3(), syringe.confToMm());
}
else if (kw(F("RMM")))
{
copyNextToTemp();
if (_temp.length())
{
if (isdigit(_temp[0]) || _temp[0] == '-')
conf.volume_value += syringe.mmToMm3(atof(_temp.c_str()));
answer(syringe.configureSyringe(conf), F("invalid length"));
copyNextToTemp();
}
Serial.printf("%sRMM: %g ul (%g mm) (target)\n", _msgHeader, syringe.confToMm3(), syringe.confToMm());
} }
else if (kw(F("DIA"))) else if (kw(F("DIA")))
{ {
...@@ -215,7 +246,7 @@ void Cli::loop (Stream& input) ...@@ -215,7 +246,7 @@ void Cli::loop (Stream& input)
conf.diameter_mm = atof(_temp.c_str()); conf.diameter_mm = atof(_temp.c_str());
answer(syringe.configureSyringe(conf), F("invalid diameter")); answer(syringe.configureSyringe(conf), F("invalid diameter"));
} }
Serial.printf("%sDIA: %g mm\n", _msgHeader.c_str(), syringe.configuration().diameter_mm); Serial.printf("%sDIA: %g mm\n", _msgHeader, syringe.configuration().diameter_mm);
} }
else if (kw(F("RVM"))) else if (kw(F("RVM")))
{ {
...@@ -226,14 +257,14 @@ void Cli::loop (Stream& input) ...@@ -226,14 +257,14 @@ void Cli::loop (Stream& input)
syringe.setMmPerRev(M5_MMREV); syringe.setMmPerRev(M5_MMREV);
else if (_temp.length() > 0) else if (_temp.length() > 0)
answer(false, F("invalid auger size: M4 or M5 are accepted")); answer(false, F("invalid auger size: M4 or M5 are accepted"));
Serial.printf("%sRVM: %g mm per revolution\n", _msgHeader.c_str(), syringe.getMmPerRev()); Serial.printf("%sRVM: %g mm per revolution\n", _msgHeader, syringe.getMmPerRev());
} }
else if (kw(F("ACC"))) else if (kw(F("ACC")))
{ {
copyNextToTemp(); copyNextToTemp();
if (_temp.length()) if (_temp.length())
syringe.setAccelMmPerSecPerSec(atof(_temp.c_str())); syringe.setAccelMmPerSecPerSec(atof(_temp.c_str()));
Serial.printf("%sACC: %g mm per second per second\n", _msgHeader.c_str(), syringe.getAccelMmPerSecPerSec()); Serial.printf("%sACC: %g mm per second per second\n", _msgHeader, syringe.getAccelMmPerSecPerSec());
} }
else if (kw(F("DIR"))) else if (kw(F("DIR")))
{ {
...@@ -248,7 +279,7 @@ void Cli::loop (Stream& input) ...@@ -248,7 +279,7 @@ void Cli::loop (Stream& input)
conf.direction = 0; conf.direction = 0;
answer(syringe.configureSyringe(conf), F("invalid direction -> INF | WDR")); answer(syringe.configureSyringe(conf), F("invalid direction -> INF | WDR"));
} }
Serial.printf("%sDIR: %s\n", _msgHeader.c_str(), Serial.printf("%sDIR: %s\n", _msgHeader,
syringe.configuration().direction > 0? "INFuse": "WithDRaw"); syringe.configuration().direction > 0? "INFuse": "WithDRaw");
} }
else if (kw(F("FIL"))) else if (kw(F("FIL")))
...@@ -269,7 +300,7 @@ void Cli::loop (Stream& input) ...@@ -269,7 +300,7 @@ void Cli::loop (Stream& input)
} }
else if (kw(F("DIS"))) else if (kw(F("DIS")))
{ {
Serial.printf("%sDIS: I %g W %g UL\n", _msgHeader.c_str(), Serial.printf("%sDIS: I %g W %g UL\n", _msgHeader,
conf.direction > 0? syringe.mmToMm3(syringe.stepToMm(syringe.whereStep())): 0, conf.direction > 0? syringe.mmToMm3(syringe.stepToMm(syringe.whereStep())): 0,
conf.direction > 0? 0 : syringe.mmToMm3(syringe.stepToMm(syringe.whereStep()))); conf.direction > 0? 0 : syringe.mmToMm3(syringe.stepToMm(syringe.whereStep())));
} }
...@@ -284,20 +315,60 @@ void Cli::loop (Stream& input) ...@@ -284,20 +315,60 @@ void Cli::loop (Stream& input)
syringe.runFromEmergency(); syringe.runFromEmergency();
answer(true); answer(true);
} }
else if (kw(F("CLKW")))
{
copyNextToTemp();
if (_temp.length() == 1)
{
if (_temp[0] == '0' || _temp[0] == '1')
{
syringe.setPushClockwise(_temp[0] == '1');
answer(true);
}
else
answer(false, F("CLKW: invalid argument"));
}
Serial.printf("%sCLKW: push %sclockwise\n", _msgHeader, syringe.getPushClockwise()? "": "anti-");
}
else if (kw(F("CONF"))) else if (kw(F("CONF")))
{ {
syringe.showConfiguration(syringe.configuration()); syringe.showConfiguration(syringe.configuration());
answer(true); answer(true);
} }
else if (kw(F("FS-LS")))
{
ls(&Serial);
answer(true);
}
else if (kw(F("FS-FORMAT")))
{
format(&Serial);
answer(true);
}
else if (kw(F("FS-CAT")))
{
copyNextToTemp();
if (_temp.length() > 0)
{
cat(_temp.c_str(), &Serial);
answer(true);
}
else
answer(false);
}
else else
{ {
Serial.printf("%sinvalid command '%s'\n", _msgHeader.c_str(), _currentInput.c_str() + _currentWordIndex); Serial.printf("%sinvalid command '%s'\n", _msgHeader, _currentInput.c_str() + _currentWordIndex);
answer(false); answer(false);
} }
} }
if (findNextWord()) if (findNextWord())
Serial.printf("%sgarbage at end of line: '%s'\n", _msgHeader.c_str(), _currentInput.c_str() + _currentWordIndex); Serial.printf("%sgarbage at end of line: '%s'\n", _msgHeader, _currentInput.c_str() + _currentWordIndex);
resetNextWord(); resetNextWord();
_currentInput.clear(); _currentInput.clear();
} }
#pragma once #pragma once
#include <Arduino.h> #include "common.h"
#include "syringe.h" #include "syringe.h"
class Cli class Cli
...@@ -13,7 +12,7 @@ private: ...@@ -13,7 +12,7 @@ private:
String _currentInput; String _currentInput;
String _temp; String _temp;
String _msgHeader = "#CLI: "; const char* _msgHeader = msgHeader; //XXX fixmeconstructorparam
int _currentWordIndex; int _currentWordIndex;
int _currentWordEndIndex; int _currentWordEndIndex;
......
...@@ -3,5 +3,10 @@ ...@@ -3,5 +3,10 @@
#include <Arduino.h> #include <Arduino.h>
#define MSGHEADER "#CLI: "
extern const char* msgHeader;
void webSetup (); void webSetup ();
void webLoop (); void webLoop ();
...@@ -43,7 +43,17 @@ public: ...@@ -43,7 +43,17 @@ public:
{ {
_stepsPerRevolution = stepsPerRevolution; _stepsPerRevolution = stepsPerRevolution;
setMmPerRev(mmPerRevolution); setMmPerRev(mmPerRevolution);
_forwardClockwise = forwardClockwise; setForwardClockwise(forwardClockwise);
}
void setForwardClockwise (bool clockwise)
{
_forwardClockwise = clockwise;
}
bool getForwardClockwise ()
{
return _forwardClockwise;
} }
void setSpeedMmPerSec (float mmPerSec) void setSpeedMmPerSec (float mmPerSec)
......
...@@ -60,11 +60,13 @@ AccelStepper stepper(AccelStepper::DRIVER, STEP, DIR); ...@@ -60,11 +60,13 @@ AccelStepper stepper(AccelStepper::DRIVER, STEP, DIR);
#include "syringe.h" #include "syringe.h"
#include "cli.h" #include "cli.h"
#include "common.h" #include "common.h"
#include "fs.h"
enum class Modes { TURN, TURNSetup, RPM, RPMSetup, INFO }; enum class Modes { TURN, TURNSetup, RPM, RPMSetup, INFO };
const char* msgHeader = MSGHEADER;
Debouncer bA, bB, bC; Debouncer bA, bB, bC;
ButtonFast bEmergency; ButtonFast bEmergency;
...@@ -276,6 +278,15 @@ void setup() ...@@ -276,6 +278,15 @@ void setup()
oled.clear(); oled.clear();
oled.println("Booting...\n"); oled.println("Booting...\n");
if (fs_init(msgHeader))
{
Serial.printf("FS initialized, dav http server started\n");
}
else
{
Serial.printf("FS: could not be started\n");
}
//syringe.setPhysical(MOTOR_STEPS * MICROSTEPS_CONF, M4_MMREV, /*forwardClockWise*/true, /*emergencySensorBehind*/false); //syringe.setPhysical(MOTOR_STEPS * MICROSTEPS_CONF, M4_MMREV, /*forwardClockWise*/true, /*emergencySensorBehind*/false);
syringe.setPhysical(MOTOR_STEPS * MICROSTEPS_CONF, M5_MMREV, /*forwardClockWise*/false, /*emergencySensorBehind*/true); syringe.setPhysical(MOTOR_STEPS * MICROSTEPS_CONF, M5_MMREV, /*forwardClockWise*/false, /*emergencySensorBehind*/true);
......
...@@ -8,7 +8,8 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf) ...@@ -8,7 +8,8 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf)
auto step = whereStep(); auto step = whereStep();
Serial.printf("# diameter: %g mm\n" Serial.printf("# push clockwise: %s"
"# 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 (target)\n" "# volume: %g uL (target)\n"
...@@ -16,6 +17,7 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf) ...@@ -16,6 +17,7 @@ void Syringe::showConfiguration (const Syringe_configuration_t& conf)
"# zeroing: %d\n" "# zeroing: %d\n"
"# emergency: %d\n" "# emergency: %d\n"
"# current position: %g mm %g ul %d steps\n", "# current position: %g mm %g ul %d steps\n",
getPushClockwise()? "yes": "no",
conf.diameter_mm, conf.diameter_mm,
conf.capacity_ul, conf.capacity_ul,
conf.rate_ul_per_s, conf.rate_ul_per_s,
......
...@@ -17,7 +17,6 @@ public: ...@@ -17,7 +17,6 @@ public:
int direction; int direction;
bool findZero; bool findZero;
} Syringe_configuration_t; } Syringe_configuration_t;
private: private:
...@@ -54,6 +53,8 @@ public: ...@@ -54,6 +53,8 @@ public:
bool configureSyringe(const Syringe_configuration_t& config); bool configureSyringe(const Syringe_configuration_t& config);
void setInitialContent(float initial_volume); void setInitialContent(float initial_volume);
void setPushClockwise (bool clockwise) { setForwardClockwise(clockwise); }
bool getPushClockwise () { return getForwardClockwise(); }
float mm3ToMm (float mm3) const; float mm3ToMm (float mm3) const;
float mmToMm3 (float mm) const; float mmToMm3 (float mm) const;
......
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