-
Notifications
You must be signed in to change notification settings - Fork 33
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add an example for configuring the driver and then using an external library for controlling the stepper. #55
Comments
I have never used AccelStepper, but if it outputs step and direction pulses in DRIVER mode then it should work fine. It would be great if you tried it and let me know if it works or not. |
I will make a pull request once I have a working example. I see that this is a duplicate issue of #52, sorry for that. My bidirectional communication does not seem to be working, so I have to sort that one out first. |
Hi Luro, did you manage to get this working? I want to use the AccelStepper library along with TMC2209, however I have never used AccelStepper and I feel, I will take too long to get it going, so if you have used AccelStepper along with TMC2209, adding an example code here will help me out! |
Yes, I was able to get it working. Just haven't had the time to make a pull request. |
Bidirectional communication and `AccelStepper`#include <AccelStepper.h>
#include <TMC2209.h>
#include <BlockNot.h>
const uint8_t DIR_PIN = 6;
const uint8_t STEP_PIN = 7;
const uint8_t EN_PIN = 0;
const float DEFAULT_SPEED = 10000.0; // NOTE: this might be too fast
// ESP32-C6
#define RX_PIN 4 // = RX1
#define TX_PIN 5 // = TX1
//ESP32-H2:
//#define RX_PIN 0 // = RX1
//#define TX_PIN 1 // = TX1
HardwareSerial & serial_stream = Serial1;
TMC2209 stepper_driver;
AccelStepper stepper(AccelStepper::DRIVER, STEP_PIN, DIR_PIN);
BlockNot stepper_communication_timer(1000, MILLISECONDS);
void setup_stepper() {
stepper_driver.setup(serial_stream);
delay(2000);
stepper_driver.setHardwareEnablePin(EN_PIN);
stepper_driver.enableCoolStep();
stepper_driver.moveUsingStepDirInterface();
//stepper_driver.useInternalSenseResistors();
stepper_driver.enableAutomaticCurrentScaling();
stepper_driver.enableAutomaticGradientAdaptation();
//stepper_driver.enableStealthChop();
stepper_driver.enable();
}
void setup() {
Serial.begin(115200);
setup_stepper();
stepper.setMaxSpeed(100000);
stepper.setSpeed(DEFAULT_SPEED);
}
void check_communication() {
if (stepper_driver.isSetupAndCommunicating()) {
Serial.println("Stepper driver is setup and communicating!");
Serial.println("Try turning driver power off to see what happens.");
} else if (stepper_driver.isCommunicatingButNotSetup()) {
Serial.println("Stepper driver is communicating but not setup!");
Serial.println("Running setup again...");
//stepper_driver.setup(serial_stream);
setup_stepper();
} else {
Serial.println("Stepper driver is not communicating!");
Serial.println("Try turning driver power on to see what happens.");
}
Serial.println();
}
void loop() {
stepper.runSpeed();
if (stepper_communication_timer.TRIGGERED) {
check_communication();
}
// stepper_driver.moveAtVelocity(10000);
} Please check that unidirectional communication is working. You can do this Unidirectional communication test#include <TMC2209.h>
const uint8_t EN_PIN = 0;
const float DEFAULT_SPEED = 10000.0; // NOTE: this might be too fast
// ESP32-C6
#define RX_PIN 4 // = RX1
#define TX_PIN 5 // = TX1
//ESP32-H2:
//#define RX_PIN 0 // = RX1
//#define TX_PIN 1 // = TX1
HardwareSerial & serial_stream = Serial1;
TMC2209 stepper_driver;
void setup_stepper() {
stepper_driver.setup(serial_stream);
delay(2000);
stepper_driver.setHardwareEnablePin(EN_PIN);
stepper_driver.enableCoolStep();
//stepper_driver.useInternalSenseResistors();
stepper_driver.enableAutomaticCurrentScaling();
stepper_driver.enableAutomaticGradientAdaptation();
//stepper_driver.enableStealthChop();
stepper_driver.enable();
}
void setup() {
Serial.begin(115200);
setup_stepper();
}
void loop() {
stepper_driver.moveAtVelocity(DEFAULT_SPEED);
} Unidirectional communication and `AccelStepper`#include <AccelStepper.h>
#include <TMC2209.h>
const uint8_t DIR_PIN = 6;
const uint8_t STEP_PIN = 7;
const uint8_t EN_PIN = 0;
const float DEFAULT_SPEED = 10000.0; // NOTE: this might be too fast
// ESP32-C6
#define RX_PIN 4 // = RX1
#define TX_PIN 5 // = TX1
//ESP32-H2:
//#define RX_PIN 0 // = RX1
//#define TX_PIN 1 // = TX1
HardwareSerial & serial_stream = Serial1;
TMC2209 stepper_driver;
AccelStepper stepper(AccelStepper::DRIVER, STEP_PIN, DIR_PIN);
void setup_stepper() {
stepper_driver.setup(serial_stream);
delay(2000);
stepper_driver.setHardwareEnablePin(EN_PIN);
stepper_driver.enableCoolStep();
stepper_driver.moveUsingStepDirInterface();
//stepper_driver.useInternalSenseResistors();
stepper_driver.enableAutomaticCurrentScaling();
stepper_driver.enableAutomaticGradientAdaptation();
//stepper_driver.enableStealthChop();
stepper_driver.enable();
}
void setup() {
Serial.begin(115200);
setup_stepper();
stepper.setMaxSpeed(100000);
stepper.setSpeed(DEFAULT_SPEED);
}
void loop() {
stepper.runSpeed();
// stepper_driver.moveAtVelocity(10000);
} I am currently trying to get my redesigned PCB working, which is why I am unable to test the above code. Here is the schematic that I am currently using: If your microcontroller is powered through USB, you can ignore the 12V -> 5V converter on the left (you should connect a GND of the microcontroller with the GND of the 12V, but this shouldn't be necessary to get the whole thing working). The microstep selector is optional as well, the stepper should move even if the MS pins are not connected. You do not have to do bidirectional communication either. The main problem I had, was that I did not use the correct pins for the |
Thanks! |
First of all, thank you for creating this library and all the documentation in the
README.md
. This was extremely helpful in getting the driver working.Right now, I am only able to control my stepper via UART, but I would like to use the STEP/DIR pins instead. If I understood the library correctly, I would still use UART, but only for setup and then delegate to the STEP/DIR pins for driving the stepper? I am thinking of something like this:
Would you mind adding an example that shows how to do this correctly with some external library?
There seem to be a few available (not sure if AccelStepper is the ideal one)
The text was updated successfully, but these errors were encountered: