The idea of moving quickly until an end stop is hit, then stopping immediately, seems to me like driving your car rapidly toward a brick will and expecting to stop it just as the bumper touches the wall. Maybe not the best plan given the laws of physics! I would tend to place the end sensor a distance before the hard stop, or anticipate the sensor by knowing when to slow down so that an attempt at a very sudden stop from quick motion is avoided.
Let's consider two cases.
First, let's assume we know where the hard stop is, relative to the start (0) position. Say it's at -600. When we get close, say at -450, we will slow down. We could also just set a target of -580, then we would stop there and could runSpeed slowly to the limit. But that seems obvious and easy.
So, second, let's assume we really don't know where the limit is, then there must be some minimal space before the hard stop. We'll go full speed until we hit the end sensor and stop as quickly as we can.
Here's the plan:
- set up an interrupt to fire when the end stop is hit. (For this demo, we'll use an second counter in the loop to put out a pulse.) This interrupt will put us in the stopNow state.
- start the motor running to a position so it accelerates to the target speed.
- when the motor gets to speed, use runSpeed to keep it going. Position is tracked, but the target is ignored.
- when we enter stopNow state, use stop() and runToPosition() to stop.
- set a new target of 0 (or -currentPosition) and run to it (accelerates and decelerates). The interrupt should be ignored.
My motor is controlled by an A4988 driver using step and direction in full-step mode. The code runs on an arduino Uno.
Here is the code:
/*
Uno sketch to drive a bipolar stepper motor using an a4988
driver (or similar) and the AccelStepper library.
This code is a response to a Forum question.
10/27/21 -jkl
*/
// Include the AccelStepper Library
#include <AccelStepper.h>
#include <elapsedMillis.h>
// Define pin connections
const int dirPin = 4;
const int stepPin = 5;
const int sensorPin = 9; // used as an end stop sensor output - driven by a timer
// hook to pin D2 - or can drive D2 directly (tie low, then disconnect to cause interrupt)
// define the time limit to run before stopping if using sensorPin
const int timeLimit = 10; // number of seconds
// State definitions
#define RSPD 01
#define RJSTR 02
#define RUN_HOME 03
#define STOP_NOW 04
// State variable
volatile int state; // must survive interrupts
// Creates an instance
AccelStepper myStepper(AccelStepper::DRIVER, stepPin, dirPin);
elapsedMillis printTime;
volatile int enabFlag = 0; // controls the end stop sensor interrupt
void setup() {
Serial.begin(115200);
attachInterrupt(0, rising, RISING);
enabFlag = 1; // enable the sensor interrupt
pinMode (sensorPin, OUTPUT);
state = RJSTR; // initial state is run, just run
// set the maximum speed, acceleration factor,
// initial speed and the target position
myStepper.setMaxSpeed(400.);
myStepper.setAcceleration(50.0);
myStepper.moveTo(-1000);
}
int lCount = 0; // elapsed seconds
void loop() {
float mSpeed;
if (printTime >= 1000) { // happens once per second
printTime = 0;
lCount++;
mSpeed = myStepper.speed();
Serial.print(mSpeed);
Serial.print(" ");
Serial.println(myStepper.currentPosition());
switch (state) {
case RSPD:
if (lCount >= timeLimit) {
digitalWrite(sensorPin,HIGH); // This will trigger interrupt
}
break;
case RJSTR:
if (mSpeed <= -200.0) {
state = RSPD; // switch to run speed state when target speed is reached
}
break;
case RUN_HOME:
case STOP_NOW: // this should never execute.
break;
}
}
switch (state) { // happens each loop - about 70KHz
case RSPD:
myStepper.runSpeed();
break;
case RJSTR:
case RUN_HOME:
myStepper.run();
break;
case STOP_NOW:
digitalWrite(sensorPin,LOW); // removes interrupt signal
myStepper.setAcceleration(200.0); // this makes motor stop much quicker!
myStepper.stop();
myStepper.runToPosition(); // brings to a stop!
myStepper.moveTo(0); // now return to home position
myStepper.setAcceleration(50.0); // slow motor acceleration back down
//myStepper.move(-myStepper.currentPosition()); // This should work also
state = RUN_HOME;
break;
}
}
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+++++++++++++++++ Interrupt service routine +++++++++++++++++++++++++++++
// Come here if rising edge on D2.
// If enable flag is true, enter state STOP_NOW
void rising() {
if (enabFlag == 1) {
state = STOP_NOW;
enabFlag = 0;
}
}