gin66 / FastAccelStepper

A high speed stepper library for Atmega 168/328p (nano), Atmega32u4, Atmega 2560, ESP32, ESP32S2, ESP32S3, ESP32C3 and Atmel SAM Due
MIT License
282 stars 67 forks source link

Motor overshoots after homing interrupt #255

Closed ham-a7 closed 2 months ago

ham-a7 commented 2 months ago

I have a linear actuator running into its end stop. The motor stall detected by the motor driver (TMC2130) then triggers an interrupt to stop movement of the motor.

I then try to run the motor in the opposite direction back to position 0 however the motor overshoots and jams itself into the other end stop.

The system is mechanically very rigid and the stall sensitivity of the driver is tuned appropriately. It seems maybe the library is still iterating up the position of the motor even after the interrupt. This would mean the library thinks it needs to travel further than it should to travel back to the zero position.

I move the motor with: Zstepper->moveTo(Z_demand_position, true); where Z_demand_position is some large value for the first movement (to ensure it hits the end stop) and 0 for the return movement.

The stall interrupt is:

void stall(){
  Zstepper->forceStop();
  Xstepper->forceStop();
  Ystepper->forceStop();
  Pstepper->forceStop();
  Serial.println("stall");
}

The setup code is:

pinMode(stall_flag_pin, INPUT_PULLUP);
  attachInterrupt(digitalPinToInterrupt(stall_flag_pin), stall, FALLING);

  // Init steppers
  engine.init();
  Xstepper = engine.stepperConnectToPin(STEP_X_PIN, DRIVER_RMT); 
  Ystepper = engine.stepperConnectToPin(STEP_Y_PIN, DRIVER_RMT);
  Zstepper = engine.stepperConnectToPin(STEP_Z_PIN, DRIVER_RMT);
  Rstepper = engine.stepperConnectToPin(STEP_R_PIN, DRIVER_RMT);

  if (Xstepper) {
    Xstepper->setDirectionPin(DIR_X_PIN);
    Xstepper->setSpeedInHz(104000); 
    Xstepper->setAcceleration(160000); 
  }

  if (Ystepper) {
    Ystepper->setDirectionPin(DIR_Y_PIN);
    Ystepper->setSpeedInHz(104000); 
    Ystepper->setAcceleration(160000); 
  }

  if (Zstepper) {
    Zstepper->setDirectionPin(DIR_Z_PIN);
    Zstepper->setSpeedInHz(136000); 
    Zstepper->setAcceleration(150000); 
  }

  if (Pstepper) {
    Rstepper->setDirectionPin(DIR_R_PIN);
    Rstepper->setSpeedInHz(104000); 
    Rstepper->setAcceleration(160000); 
  }

I am using an Arduino Nano ESP32 with the version 0.30.12 of the library from Platformio.

gin66 commented 2 months ago

On forceStop(): The stepper command queue will be processed, but no further commands are added. This means, that the stepper can be expected to stop within approx. 20ms

That ~20ms is executed at full speed. At 104000steps/s the stepper will receive still ~2000 steps with stalled motor. If the motor has started from position 0 and then run into this stall at e.g. 1.000.000, then the motor stopped movement at the mechanical position 1.000.000, but FastAccelStepper has issued 1.002.000 steps and as such thinks the motor is at that position. On command to moveTo(0) FastAccelStepper will issue 1.002.000 steps in the other direction. As the stepper motor starts from mechanical position 1.000.000, it will run to -2.000 aka 2000 steps into the end stop at zero.

Is this interpretation match to your finding ?

ham-a7 commented 2 months ago

Yes this explains the overshoot. Changing the 2nd demand position to 2000 removes the overshoot.

Is the execution time of forceStop() consitently 20ms or can it be anything 0ms to 20ms? If it was consistent, the 2000 steps could be subtracted from the motor position whenever there is a stall.

A more robust solution to get accurate positioning after a stall is to rehome the motor at the 0 position every time there is a stall interrupt.

The other solution I can think of to reduce this positional error is to run the motor at a slower speed if a stall is expected.

Thanks for your help

gin66 commented 2 months ago

It is not consistent 20ms. The stepper commands are buffered in a queue, which covers up to 20ms into the future. The ramp generator fills up every 4ms and the pulse generator continuously removes commands from the queue. So for a stepper running at full speed, it may anything between ~16 to ~20ms. BTW: In the current master branch, this planning ahead time is configurable.

If a stall is detected and then the motor is running at slower speed, it will not fix the mismatch. It just will not run as fast into the other end stop.

Why does the stall happen at all ? Is this required by your application and can happen any time ? Or is the stall kind of another end stop, which unfortunately causes a mechanical position mismatch ? If the latter, then proposal would be to just run into the stall and ignore the mismatch, then run full speed to e.g. position 3000 and then reduce to a very slow speed until the 0 endstop is reached. This should give sufficient information to calculate aka measure the steps between those end points.

ham-a7 commented 2 months ago

Yes the stall is required for the application. It is a pick and place application. The position of the stall is arbitrary and depends on the size of the object being picked up however it is known that a stall will occur during a specific motion so your approach would work.