mirror of
https://github.com/usatiuk/EggbotWireless.git
synced 2025-10-26 16:57:48 +01:00
timer-driven stepper driver
This commit is contained in:
1
Firmware/EggbotWireless/.gitignore
vendored
1
Firmware/EggbotWireless/.gitignore
vendored
@@ -6,3 +6,4 @@
|
|||||||
.vscode/launch.json
|
.vscode/launch.json
|
||||||
.history
|
.history
|
||||||
.vscode
|
.vscode
|
||||||
|
.directory
|
||||||
@@ -3,20 +3,22 @@
|
|||||||
|
|
||||||
class Stepper {
|
class Stepper {
|
||||||
private:
|
private:
|
||||||
unsigned int stepsPerRevolution;
|
int stepsPerRevolution;
|
||||||
int pin1;
|
int pin1;
|
||||||
int pin2;
|
int pin2;
|
||||||
int pin3;
|
int pin3;
|
||||||
int pin4;
|
int pin4;
|
||||||
int speedDelay;
|
int curStep = 1;
|
||||||
|
int remainingSteps;
|
||||||
|
bool direction;
|
||||||
void clockwise();
|
void clockwise();
|
||||||
void counterClockwise();
|
void counterClockwise();
|
||||||
|
|
||||||
public:
|
public:
|
||||||
Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution, int rpm);
|
Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution);
|
||||||
~Stepper();
|
|
||||||
void step(int steps);
|
void step(int steps);
|
||||||
void move(float degrees);
|
void rotate(float degrees);
|
||||||
|
void doStep();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
11
Firmware/EggbotWireless/include/StepperTimer.h
Normal file
11
Firmware/EggbotWireless/include/StepperTimer.h
Normal file
@@ -0,0 +1,11 @@
|
|||||||
|
#include <Ticker.h>
|
||||||
|
#include "Stepper.h"
|
||||||
|
|
||||||
|
#ifndef STEPPER_TIMER_H
|
||||||
|
#define STEPPER_TIMER_H
|
||||||
|
|
||||||
|
void stepperTimerInit(int rpm, int stepsPerRevolution);
|
||||||
|
void stepperTimerSetStepper(int num, Stepper *stepper);
|
||||||
|
void stepperTimerTick();
|
||||||
|
|
||||||
|
#endif
|
||||||
@@ -12,3 +12,4 @@
|
|||||||
platform = espressif8266
|
platform = espressif8266
|
||||||
board = d1_mini
|
board = d1_mini
|
||||||
framework = arduino
|
framework = arduino
|
||||||
|
monitor_speed = 115200
|
||||||
@@ -2,107 +2,120 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
|
||||||
void Stepper::clockwise() {
|
void Stepper::clockwise() {
|
||||||
digitalWrite(pin4, HIGH);
|
switch (curStep) {
|
||||||
digitalWrite(pin3, LOW);
|
case 1:
|
||||||
digitalWrite(pin2, LOW);
|
digitalWrite(pin4, HIGH);
|
||||||
digitalWrite(pin1, LOW);
|
digitalWrite(pin3, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, LOW);
|
||||||
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, HIGH);
|
break;
|
||||||
digitalWrite(pin3, HIGH);
|
case 2:
|
||||||
digitalWrite(pin2, LOW);
|
digitalWrite(pin4, HIGH);
|
||||||
digitalWrite(pin1, LOW);
|
digitalWrite(pin3, HIGH);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, LOW);
|
||||||
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
break;
|
||||||
digitalWrite(pin3, HIGH);
|
case 3:
|
||||||
digitalWrite(pin2, LOW);
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
digitalWrite(pin3, HIGH);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, LOW);
|
||||||
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
break;
|
||||||
digitalWrite(pin3, HIGH);
|
case 4:
|
||||||
digitalWrite(pin2, HIGH);
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
digitalWrite(pin3, HIGH);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, HIGH);
|
||||||
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
break;
|
||||||
digitalWrite(pin3, LOW);
|
case 5:
|
||||||
digitalWrite(pin2, HIGH);
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
digitalWrite(pin3, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, HIGH);
|
||||||
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
break;
|
||||||
digitalWrite(pin3, LOW);
|
case 6:
|
||||||
digitalWrite(pin2, HIGH);
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, HIGH);
|
digitalWrite(pin3, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, HIGH);
|
||||||
|
digitalWrite(pin1, HIGH);
|
||||||
digitalWrite(pin4, LOW);
|
break;
|
||||||
digitalWrite(pin3, LOW);
|
case 7:
|
||||||
digitalWrite(pin2, LOW);
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, HIGH);
|
digitalWrite(pin3, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, LOW);
|
||||||
|
digitalWrite(pin1, HIGH);
|
||||||
digitalWrite(pin4, HIGH);
|
break;
|
||||||
digitalWrite(pin3, LOW);
|
case 8:
|
||||||
digitalWrite(pin2, LOW);
|
digitalWrite(pin4, HIGH);
|
||||||
digitalWrite(pin1, HIGH);
|
digitalWrite(pin3, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin2, LOW);
|
||||||
|
digitalWrite(pin1, HIGH);
|
||||||
|
}
|
||||||
|
if (curStep == 8) {
|
||||||
|
curStep = 1;
|
||||||
|
} else {
|
||||||
|
curStep++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Stepper::counterClockwise() {
|
void Stepper::counterClockwise() {
|
||||||
digitalWrite(pin1, HIGH);
|
switch (curStep) {
|
||||||
digitalWrite(pin2, LOW);
|
case 1:
|
||||||
digitalWrite(pin3, LOW);
|
digitalWrite(pin1, HIGH);
|
||||||
digitalWrite(pin4, LOW);
|
digitalWrite(pin2, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, LOW);
|
||||||
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, HIGH);
|
break;
|
||||||
digitalWrite(pin2, HIGH);
|
case 2:
|
||||||
digitalWrite(pin3, LOW);
|
digitalWrite(pin1, HIGH);
|
||||||
digitalWrite(pin4, LOW);
|
digitalWrite(pin2, HIGH);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, LOW);
|
||||||
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
break;
|
||||||
digitalWrite(pin2, HIGH);
|
case 3:
|
||||||
digitalWrite(pin3, LOW);
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
digitalWrite(pin2, HIGH);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, LOW);
|
||||||
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
break;
|
||||||
digitalWrite(pin2, HIGH);
|
case 4:
|
||||||
digitalWrite(pin3, HIGH);
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
digitalWrite(pin2, HIGH);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, HIGH);
|
||||||
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
break;
|
||||||
digitalWrite(pin2, LOW);
|
case 5:
|
||||||
digitalWrite(pin3, HIGH);
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, LOW);
|
digitalWrite(pin2, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, HIGH);
|
||||||
|
digitalWrite(pin4, LOW);
|
||||||
digitalWrite(pin1, LOW);
|
break;
|
||||||
digitalWrite(pin2, LOW);
|
case 6:
|
||||||
digitalWrite(pin3, HIGH);
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, HIGH);
|
digitalWrite(pin2, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, HIGH);
|
||||||
|
digitalWrite(pin4, HIGH);
|
||||||
digitalWrite(pin1, LOW);
|
break;
|
||||||
digitalWrite(pin2, LOW);
|
case 7:
|
||||||
digitalWrite(pin3, LOW);
|
digitalWrite(pin1, LOW);
|
||||||
digitalWrite(pin4, HIGH);
|
digitalWrite(pin2, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, LOW);
|
||||||
|
digitalWrite(pin4, HIGH);
|
||||||
digitalWrite(pin1, HIGH);
|
break;
|
||||||
digitalWrite(pin2, LOW);
|
case 8:
|
||||||
digitalWrite(pin3, LOW);
|
digitalWrite(pin1, HIGH);
|
||||||
digitalWrite(pin4, HIGH);
|
digitalWrite(pin2, LOW);
|
||||||
delay(speedDelay);
|
digitalWrite(pin3, LOW);
|
||||||
|
digitalWrite(pin4, HIGH);
|
||||||
|
}
|
||||||
|
if (curStep == 8) {
|
||||||
|
curStep = 1;
|
||||||
|
} else {
|
||||||
|
curStep++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
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 rpm)
|
|
||||||
: pin1(pin1),
|
: pin1(pin1),
|
||||||
pin2(pin2),
|
pin2(pin2),
|
||||||
pin3(pin3),
|
pin3(pin3),
|
||||||
@@ -112,26 +125,30 @@ Stepper::Stepper(int pin1, int pin2, int pin3, int pin4, int stepsPerRevolution,
|
|||||||
pinMode(pin2, OUTPUT);
|
pinMode(pin2, OUTPUT);
|
||||||
pinMode(pin3, OUTPUT);
|
pinMode(pin3, OUTPUT);
|
||||||
pinMode(pin4, OUTPUT);
|
pinMode(pin4, OUTPUT);
|
||||||
|
|
||||||
speedDelay = 60 * 1000 / (rpm * stepsPerRevolution);
|
|
||||||
}
|
}
|
||||||
Stepper::~Stepper() {}
|
|
||||||
|
|
||||||
void Stepper::step(int steps) {
|
void Stepper::doStep() {
|
||||||
int halfsteps = steps / 8;
|
if(remainingSteps > 0) {
|
||||||
if (halfsteps > 0) {
|
if(direction){
|
||||||
for (int i = 0; i < halfsteps; i++) {
|
|
||||||
clockwise();
|
clockwise();
|
||||||
}
|
} else {
|
||||||
} else if (halfsteps < 0) {
|
|
||||||
halfsteps = abs(halfsteps);
|
|
||||||
for (int i = 0; i < halfsteps; i++) {
|
|
||||||
counterClockwise();
|
counterClockwise();
|
||||||
}
|
}
|
||||||
|
remainingSteps--;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Stepper::move(float degrees) {
|
void Stepper::step(int steps) {
|
||||||
|
if (steps > 0) {
|
||||||
|
direction = true;
|
||||||
|
remainingSteps = steps;
|
||||||
|
} else {
|
||||||
|
direction = false;
|
||||||
|
remainingSteps = abs(steps);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Stepper::rotate(float degrees) {
|
||||||
int steps = (degrees * stepsPerRevolution) / 360;
|
int steps = (degrees * stepsPerRevolution) / 360;
|
||||||
step(steps);
|
step(steps);
|
||||||
}
|
}
|
||||||
22
Firmware/EggbotWireless/src/StepperTimer.cpp
Normal file
22
Firmware/EggbotWireless/src/StepperTimer.cpp
Normal file
@@ -0,0 +1,22 @@
|
|||||||
|
#include "StepperTimer.h"
|
||||||
|
#include "Stepper.h"
|
||||||
|
|
||||||
|
int speedDelay;
|
||||||
|
Ticker stepperTicker;
|
||||||
|
Stepper *steppers[2];
|
||||||
|
|
||||||
|
void stepperTimerInit(int rpm, int stepsPerRevolution)
|
||||||
|
{
|
||||||
|
speedDelay = 60 * 1000 / (rpm * stepsPerRevolution);
|
||||||
|
stepperTicker.attach_ms(speedDelay, stepperTimerTick);
|
||||||
|
}
|
||||||
|
|
||||||
|
void stepperTimerSetStepper(int num, Stepper *stepper) {
|
||||||
|
steppers[num] = stepper;
|
||||||
|
}
|
||||||
|
|
||||||
|
void stepperTimerTick() {
|
||||||
|
for (int i = 0; i < 2; i++) {
|
||||||
|
steppers[i]->doStep();
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,16 +1,21 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "Stepper.h"
|
|
||||||
#include "Pen.h"
|
#include "Pen.h"
|
||||||
|
#include "Stepper.h"
|
||||||
|
#include "StepperTimer.h"
|
||||||
|
|
||||||
|
#define STEPS_PER_REVOLUTION 4076
|
||||||
|
|
||||||
|
Stepper eggStepper(D1, D2, D3, D4, STEPS_PER_REVOLUTION);
|
||||||
|
Stepper servoStepper(D5, D6, D7, D8, STEPS_PER_REVOLUTION);
|
||||||
|
|
||||||
Stepper eggStepper(D1, D2, D3, D4, 4076, 6);
|
|
||||||
Stepper servoStepper(D5, D6, D7, D8, 4076, 6);
|
|
||||||
Pen pen(D0, 180, 80);
|
Pen pen(D0, 180, 80);
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
stepperTimerSetStepper(0, &eggStepper);
|
||||||
|
stepperTimerSetStepper(1, &servoStepper);
|
||||||
|
stepperTimerInit(6, STEPS_PER_REVOLUTION);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
Serial.print("Hello!\n");
|
|
||||||
delay(1000);
|
|
||||||
}
|
}
|
||||||
Reference in New Issue
Block a user