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

Merge branch 'master' into 'master'

Master

See merge request !12
parents 8fae7851 1e648abc
No related branches found
No related tags found
1 merge request!12Master
......@@ -25,6 +25,7 @@ lib_deps =
adafruit/Adafruit BusIO@^1.11.5
SPI
s00500/ESPUI@^2.0.0
waspinator/AccelStepper@^1.61
monitor_speed = 74880
upload_speed = 921600
\ No newline at end of file
......@@ -8,7 +8,7 @@
#define STAPSK ""
#else
#define STASSID "laas-welcome"
#define STAPSK "WifiLAAS2022" // this password is wrong
#define STAPSK "WifiLAAS2018" // this password is wrong
#endif
#define NAME "PousseSeringue"
......@@ -48,29 +48,26 @@
#include <ESP8266WiFi.h> // internal, wifi library
#include <DNSServer.h> // internal, access point mode
#if !CORE_MOCK
#include <SSD1306AsciiWire.h> // https://github.com/greiman/SSD1306Ascii
#include <A4988.h> // https://github.com/laurb9/StepperDriver
#include <AccelStepper.h>
#endif // !CORE_MOCK
#include "Debouncer.h" // local, debouncer, short counter, long detector
#include "common.h"
enum class Modes { TURN, TURNSetup, RPM, RPMSetup, INFO };
millis_t nowMs; // to update on main loop(): "nowMs = millis();"
Debouncer<nowMs> bA, bB, bC;
#if !CORE_MOCK
A4988 a4988(MOTOR_STEPS, DIR, STEP, SLEEP);
AccelStepper stepper(AccelStepper::DRIVER, STEP,DIR);
SSD1306AsciiWire oled;
#endif // !CORE_MOCK
constexpr int DNS_PORT = 53;
......@@ -93,6 +90,8 @@ int stepDurationMs = STEP_DURATION_DEFAULT_MS;
float stepsPerDuration2rpm () { return 60.0 * stepsPerDuration / ((MOTOR_STEPS * MICROSTEPS_CONF) * (stepDurationMs / 1000.0)); }
int rpming = 0; // -1, 0 or +1
const char* oledMode ()
{
switch (mode)
......@@ -216,7 +215,7 @@ void buttons (int shortp, int longp)
void setup()
{
Serial.begin(74880);
Serial.begin(9600);
Serial.setDebugOutput(true);
#if !CORE_MOCK
Wire.begin();
......@@ -231,12 +230,10 @@ void setup()
oled.clear();
oled.println("Booting...\n");
#endif // !CORE_MOCK
#if !CORE_MOCK
a4988.begin(STEPPER_RPM); // some value is necessary
a4988.setEnableActiveState(LOW);
a4988.setMicrostep(MICROSTEPS_CONF);
a4988.enable();
#if !CORE_MOCK
stepper.setMaxSpeed(10000);
stepper.setAcceleration(10000);
stepper.moveTo(200);
#endif // !CORE_MOCK
uint8_t mac[6];
......@@ -307,35 +304,15 @@ void loop()
}
// Stepper
// MOVE THIS BLOCK INTO A TIMER/ISR
// (it is randomly slowed down by prints / web / wifi)
// (or? use A4988 RPM mode, related: a4988.begin(STEPPER_RPM);)
if (lastMoveMs - nowMs > (millis_t)stepDurationMs)
#if !CORE_MOCK
if (stepper.distanceToGo() == 0)
{
if (rpming && move < MOTOR_STEPS * MICROSTEPS_CONF && move > -(MOTOR_STEPS * MICROSTEPS_CONF))
{
move += rpming * MOTOR_STEPS * MICROSTEPS_CONF;
//Serial.printf("feeding %d\n", move);
}
if (move >= stepsPerDuration)
{
move -= stepsPerDuration;
#if !CORE_MOCK
a4988.move(stepsPerDuration); // forward revolution
#endif // !CORE_MOCK
}
if (move <= -stepsPerDuration)
{
move += stepsPerDuration;
#if !CORE_MOCK
a4988.move(-stepsPerDuration); // backward revolution
#endif // !CORE_MOCK
}
lastMoveMs += stepDurationMs;
stepper.moveTo(-stepper.currentPosition());
Serial.println("Rotating Motor in opposite direction...");
}
stepper.run();
#endif // !CORE_MOCK
webLoop();
dnsServer.processNextRequest(); // AP redirection
}
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