mirror of
https://github.com/usatiuk/EggbotWireless.git
synced 2025-10-26 08:47:49 +01:00
some adjustments to stepper control mechanism
This commit is contained in:
@@ -13,4 +13,6 @@ platform = espressif8266
|
||||
board = d1_mini
|
||||
framework = arduino
|
||||
monitor_speed = 115200
|
||||
board_build.f_cpu = 160000000L
|
||||
board_build.f_cpu = 160000000L
|
||||
|
||||
upload_port=/dev/ttyUSB0
|
||||
@@ -68,13 +68,19 @@ void loop() {
|
||||
if (inChar == '\n') {
|
||||
inString.trim();
|
||||
sendCommand(parseGCode(inString));
|
||||
unsigned long reqTime = millis();
|
||||
while (waitingForNext) {
|
||||
while (!Wire.available()) {
|
||||
if (millis() - reqTime > 500) {
|
||||
Wire.requestFrom(8, 1);
|
||||
reqTime = millis();
|
||||
}
|
||||
}
|
||||
int response = Wire.read();
|
||||
if (response == WAIT) {
|
||||
delay(1);
|
||||
Wire.requestFrom(8, 1);
|
||||
reqTime = millis();
|
||||
} else if (response == NEXT) {
|
||||
Serial.println("OK");
|
||||
waitingForNext = false;
|
||||
|
||||
@@ -21,12 +21,10 @@ Stepper servoStepper(28, 29, -STEPS_PER_REVOLUTION, X_LIMIT,
|
||||
|
||||
Pen pen(23, 100, 180);
|
||||
|
||||
float eggStepperDelay;
|
||||
float servoStepperDelay;
|
||||
unsigned int eggStepperDelay;
|
||||
unsigned int servoStepperDelay;
|
||||
|
||||
float eggStepperRPM;
|
||||
float servoStepperRPM;
|
||||
|
||||
bool needAdjust;
|
||||
|
||||
#endif
|
||||
@@ -5,9 +5,11 @@
|
||||
#include "common/Commands.h"
|
||||
|
||||
int curRPM = DEF_RPM;
|
||||
int adjustDelay = 10;
|
||||
int adjustDelay = 100;
|
||||
bool needAdjust;
|
||||
bool moving;
|
||||
|
||||
float calculateDelay(float rpm, int stepsPerRevolution) {
|
||||
int calculateDelay(float rpm, int stepsPerRevolution) {
|
||||
return ((float)1000 * (float)60) / (rpm * (float)stepsPerRevolution);
|
||||
}
|
||||
|
||||
@@ -78,6 +80,7 @@ void requestEvent() {
|
||||
|
||||
void execCommand(float *command) {
|
||||
executing = true;
|
||||
moving = false;
|
||||
if (command[0] == G01 || command[0] == G00) {
|
||||
if (command[0] == G01) {
|
||||
needAdjust = true;
|
||||
@@ -101,9 +104,11 @@ void execCommand(float *command) {
|
||||
pen.disengage();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
adjustRPM();
|
||||
|
||||
moving = true;
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
@@ -117,20 +122,24 @@ void setup() {
|
||||
Serial.println("Hello!");
|
||||
eggStepperRPM = servoStepperRPM = curRPM;
|
||||
OCR2 = 250;
|
||||
TCCR2 |= (1 << WGM12) | (1 << CS22);
|
||||
TCCR2 |= (1 << WGM20) | (1 << CS22);
|
||||
TIMSK |= (1 << OCIE2);
|
||||
sei();
|
||||
servoStepper.setPos(X_LIMIT);
|
||||
pen.init();
|
||||
}
|
||||
|
||||
unsigned int ms = 0;
|
||||
|
||||
ISR(TIMER2_COMP_vect) {
|
||||
unsigned long ms = millis();
|
||||
if (fmod(ms, eggStepperDelay) < 1) {
|
||||
eggStepper.doStep();
|
||||
}
|
||||
if (fmod(ms, servoStepperDelay) < 1) {
|
||||
servoStepper.doStep();
|
||||
ms++;
|
||||
if (moving) {
|
||||
if (ms % eggStepperDelay == 0) {
|
||||
eggStepper.doStep();
|
||||
}
|
||||
if (ms % servoStepperDelay == 0) {
|
||||
servoStepper.doStep();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user