mirror of
https://github.com/usatiuk/EggbotWireless.git
synced 2025-10-26 16:57:48 +01:00
stepper backlash compensation
Signed-off-by: Stepan Usatyuk <usaatyuk@ustk.me>
This commit is contained in:
@@ -10,15 +10,17 @@ class Stepper {
|
|||||||
int pin4;
|
int pin4;
|
||||||
int curStep = 1;
|
int curStep = 1;
|
||||||
int remainingSteps;
|
int remainingSteps;
|
||||||
|
int backlashSteps;
|
||||||
bool direction;
|
bool direction;
|
||||||
void clockwise();
|
void clockwise();
|
||||||
void counterClockwise();
|
void counterClockwise();
|
||||||
|
|
||||||
public:
|
public:
|
||||||
Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution);
|
Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution, int backlashSteps);
|
||||||
void step(int steps);
|
void step(int steps);
|
||||||
void rotate(float degrees);
|
void rotate(float degrees);
|
||||||
void doStep();
|
void doStep();
|
||||||
|
bool finished();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
@@ -115,12 +115,14 @@ void Stepper::counterClockwise() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
Stepper::Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution)
|
Stepper::Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution,
|
||||||
|
int backlashSteps)
|
||||||
: pin1(pin1),
|
: pin1(pin1),
|
||||||
pin2(pin2),
|
pin2(pin2),
|
||||||
pin3(pin3),
|
pin3(pin3),
|
||||||
pin4(pin4),
|
pin4(pin4),
|
||||||
stepsPerRevolution(stepsPerRevolution) {
|
stepsPerRevolution(stepsPerRevolution),
|
||||||
|
backlashSteps(backlashSteps) {
|
||||||
pinMode(pin1, OUTPUT);
|
pinMode(pin1, OUTPUT);
|
||||||
pinMode(pin2, OUTPUT);
|
pinMode(pin2, OUTPUT);
|
||||||
pinMode(pin3, OUTPUT);
|
pinMode(pin3, OUTPUT);
|
||||||
@@ -128,8 +130,8 @@ Stepper::Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution)
|
|||||||
}
|
}
|
||||||
|
|
||||||
void Stepper::doStep() {
|
void Stepper::doStep() {
|
||||||
if(remainingSteps > 0) {
|
if (remainingSteps > 0) {
|
||||||
if(direction){
|
if (direction) {
|
||||||
clockwise();
|
clockwise();
|
||||||
} else {
|
} else {
|
||||||
counterClockwise();
|
counterClockwise();
|
||||||
@@ -140,11 +142,17 @@ void Stepper::doStep() {
|
|||||||
|
|
||||||
void Stepper::step(int steps) {
|
void Stepper::step(int steps) {
|
||||||
if (steps > 0) {
|
if (steps > 0) {
|
||||||
|
if (!direction) {
|
||||||
|
remainingSteps += backlashSteps;
|
||||||
|
}
|
||||||
direction = true;
|
direction = true;
|
||||||
remainingSteps = steps;
|
remainingSteps += steps;
|
||||||
} else {
|
} else {
|
||||||
|
if (direction) {
|
||||||
|
remainingSteps += backlashSteps;
|
||||||
|
}
|
||||||
direction = false;
|
direction = false;
|
||||||
remainingSteps = abs(steps);
|
remainingSteps += abs(steps);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -152,3 +160,7 @@ void Stepper::rotate(float degrees) {
|
|||||||
int steps = (degrees * stepsPerRevolution) / 360;
|
int steps = (degrees * stepsPerRevolution) / 360;
|
||||||
step(steps);
|
step(steps);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Stepper::finished() {
|
||||||
|
return remainingSteps == 0;
|
||||||
|
}
|
||||||
@@ -4,18 +4,29 @@
|
|||||||
#include "StepperTimer.h"
|
#include "StepperTimer.h"
|
||||||
|
|
||||||
#define STEPS_PER_REVOLUTION 4076
|
#define STEPS_PER_REVOLUTION 4076
|
||||||
|
#define BACKLASH_STEPS 40
|
||||||
|
#define RPM 6
|
||||||
|
|
||||||
Stepper eggStepper(D1, D2, D3, D4, STEPS_PER_REVOLUTION);
|
Stepper eggStepper(D1, D2, D3, D4, STEPS_PER_REVOLUTION, BACKLASH_STEPS);
|
||||||
Stepper servoStepper(D5, D6, D7, D8, STEPS_PER_REVOLUTION);
|
Stepper servoStepper(D5, D6, D7, D8, STEPS_PER_REVOLUTION, BACKLASH_STEPS);
|
||||||
|
|
||||||
Pen pen(D0, 180, 80);
|
Pen pen(D0, 180, 80);
|
||||||
|
|
||||||
|
String inString;
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
stepperTimerSetStepper(0, &eggStepper);
|
stepperTimerSetStepper(0, &eggStepper);
|
||||||
stepperTimerSetStepper(1, &servoStepper);
|
stepperTimerSetStepper(1, &servoStepper);
|
||||||
stepperTimerInit(6, STEPS_PER_REVOLUTION);
|
stepperTimerInit(RPM, STEPS_PER_REVOLUTION);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
|
while (Serial.available() > 0) {
|
||||||
|
int inChar = Serial.read();
|
||||||
|
Serial.write(inChar);
|
||||||
|
|
||||||
|
if (inChar == '\n') {
|
||||||
|
inString = "";
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
Reference in New Issue
Block a user