AccelStepper tests
parent
43c5fe0142
commit
bb8327de4b
|
@ -16,3 +16,4 @@ framework = arduino
|
|||
lib_deps =
|
||||
SPI
|
||||
TMCStepper
|
||||
AccelStepper
|
||||
|
|
67
src/main.cpp
67
src/main.cpp
|
@ -5,6 +5,7 @@
|
|||
*/
|
||||
|
||||
#include <TMCStepper.h>
|
||||
#include <AccelStepper.h>
|
||||
|
||||
#define EN_PIN 7 // Enable
|
||||
#define DIR_PIN 9 // Direction
|
||||
|
@ -37,12 +38,20 @@
|
|||
//TMC2209Stepper driver(&SERIAL_PORT, R_SENSE, DRIVER_ADDRESS);
|
||||
TMC2209Stepper driver(SW_RX, SW_TX, R_SENSE, DRIVER_ADDRESS);
|
||||
|
||||
AccelStepper accel = AccelStepper(accel.DRIVER, STEP_PIN, DIR_PIN);
|
||||
|
||||
#define MICROSTEPS 256
|
||||
#define STEPS_PER_REV 200 * MICROSTEPS
|
||||
|
||||
void setup() {
|
||||
pinMode(EN_PIN, OUTPUT);
|
||||
pinMode(STEP_PIN, OUTPUT);
|
||||
pinMode(DIR_PIN, OUTPUT);
|
||||
digitalWrite(EN_PIN, LOW); // Enable driver in hardware
|
||||
|
||||
Serial.begin(9600);
|
||||
Serial.println("Start...");
|
||||
|
||||
// Enable one according to your setup
|
||||
//SPI.begin(); // SPI drivers
|
||||
//SERIAL_PORT.begin(115200); // HW UART drivers
|
||||
|
@ -50,26 +59,58 @@ void setup() {
|
|||
|
||||
driver.begin(); // SPI: Init CS pins and possible SW SPI pins
|
||||
// UART: Init SW UART (if selected) with default 115200 baudrate
|
||||
driver.toff(5); // Enables driver in software
|
||||
driver.rms_current(400); // Set motor RMS current
|
||||
// driver.microsteps(16); // Set microsteps to 1/16th
|
||||
driver.toff(4); // Enables driver in software
|
||||
driver.rms_current(300); // Set motor RMS current
|
||||
driver.microsteps(MICROSTEPS); // Set microsteps to 1/16th
|
||||
|
||||
// driver.en_pwm_mode(true); // Toggle stealthChop on TMC2130/2160/5130/5160
|
||||
// driver.en_spreadCycle(false); // Toggle spreadCycle on TMC2208/2209/2224
|
||||
driver.pwm_autoscale(true); // Needed for stealthChop
|
||||
// driver.pwm_autoscale(true); // Needed for stealthChop
|
||||
|
||||
Serial.print("DRV_STATUS=0b");
|
||||
Serial.println(driver.DRV_STATUS(), BIN);
|
||||
|
||||
accel.setMaxSpeed(50000.0);
|
||||
accel.setAcceleration(2000.0);
|
||||
accel.setMinPulseWidth(1);
|
||||
accel.setEnablePin(EN_PIN);
|
||||
accel.setPinsInverted(false, false, true);
|
||||
accel.enableOutputs();
|
||||
}
|
||||
|
||||
bool shaft = false;
|
||||
unsigned int stepsDelay = 80;
|
||||
|
||||
void loop() {
|
||||
// Run 5000 steps and switch direction in software
|
||||
for (uint16_t i = 3200; i>0; i--) {
|
||||
digitalWrite(STEP_PIN, HIGH);
|
||||
delayMicroseconds(100);
|
||||
digitalWrite(STEP_PIN, LOW);
|
||||
delayMicroseconds(120);
|
||||
// if (Serial.available()) {
|
||||
// char c = Serial.read();
|
||||
// if (c == 'r') {
|
||||
// shaft = !shaft;
|
||||
// driver.shaft(shaft);
|
||||
// Serial.println("Shaft reversed");
|
||||
// } else if (c == '+') {
|
||||
// stepsDelay *= 0.8;
|
||||
// Serial.println("Speed: " + String(stepsDelay));
|
||||
// } else if (c == '-') {
|
||||
// stepsDelay *= 1.2;
|
||||
// Serial.println("Speed: " + String(stepsDelay));
|
||||
// }
|
||||
// }
|
||||
|
||||
// // Run 5000 steps and switch direction in software
|
||||
// for (uint32_t i = 17066; i>0; i--) {
|
||||
// digitalWrite(STEP_PIN, HIGH);
|
||||
// delayMicroseconds(10);
|
||||
// digitalWrite(STEP_PIN, LOW);
|
||||
// delayMicroseconds(stepsDelay);
|
||||
// }
|
||||
// delay(500);
|
||||
|
||||
if (accel.distanceToGo() == 0) {
|
||||
accel.disableOutputs();
|
||||
delay(500);
|
||||
accel.move(17066);
|
||||
accel.enableOutputs();
|
||||
}
|
||||
shaft = !shaft;
|
||||
driver.shaft(shaft);
|
||||
delay(500);
|
||||
accel.run();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue