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