Skip to content
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

RotateController with attached Stepper can cause stepper position freeze (in TeensyStep > 2.0.0) #150

Open
baender opened this issue Mar 17, 2023 · 4 comments

Comments

@baender
Copy link

baender commented Mar 17, 2023

Hi

tl;dr

in commit 638d653 (after release of 2.0.0) a single line change in PIT.h was introduced, when reverted (even with TeensyStep > 2.0.0) this issue seems resolved.




Hi again,

while struggeling with an older issue (#111 ) I got more down the rabit hole and very close to the actual problem. Therefore, I decided to close the old and create a new issue.

I run a bare Teensy 3.6, nothing attached and the github release 2.3.0 of TeensyStep.

The provided code attaches a stepper to the rotate controller and then overrides the speed of that controller, toggling from clockwise to counter-clockwise.

However, when choosing a certain acceleration and velocities combination the stepper position freezes on a change in direction (the hardware pins for step and dir stop working as well). The rotate controller keeps on running.

After running maaaany combinations of acceleration and speed, I found a very strange but extremly consistent pattern that can be put into a simple mathematical formula:

$$v_{critical}={a \over 200} n \quad \quad | \quad n=1,2,3...$$

The values for acceleration in the example is 200.000 which means the critical velocity is every 1.000 steps / s. Choosing a value divisable by 1.000 steps / s for forwardSpeed and backwardSpeed (like in the example with 100.000 steps / s) leads to a complete
freeze on change of direction (see image).

On top of that, one can rescue the freeze state. If one direction is set to a critical velocity, the stepper unfreezes if the other velocity is set to:

$$v_{rescue}=v_{critical} \pm \Delta v \quad \quad | \quad 0 < \Delta v \le 250$$

All in all this seems very much like Voodoo. Nevertheless, I ran hundres of tests with various versions of the TeensyStep library. This is also how I found the (assumed) problem. I realised that these formulas for freeze and unfreeze did not hold for TeensyStep-2.0.0. So I went through the commit history and found the commit that introduced this behaviour (commit 638d653).

The change seemed very isolated so I tried to run TeensyStep 2.3.0 with only this little change reversed to Version 2.0.0 and everything works as expected. Unfortunately, my understanding of the library is not deep enough to fully understand the consequences. I will run more experiments to see whether this introduces other unwanted side-effects. Otherwise I will use version 2.3.0 with this single line from 2.0.0 as a fix (or even use 2.0.0 entirely).

Perhaps this is something you want to have a look into.

Cheers and thanks again for this awesome library

#include <Arduino.h>
#include <TimerOne.h>
#include <TeensyStep.h>

// v_critical = a / 200 * n  | n = 1, 2, 3....
// v_rescue = v_critical +/- 250 steps / s

constexpr uint32_t toggleDirectionInterval = 2000;    // milliseconds
constexpr uint32_t printInterval           = 5000;    // microseconds
constexpr uint32_t maxAcceleration         = 200000;  // steps per second^2
constexpr int32_t  forwardSpeed            = 100000;  // steps per second
constexpr int32_t  backwardSpeed           = 100000;  // steps per second
constexpr int32_t  maxSpeed                = 300000;  // steps per second

int32_t targetSpeed = 0;
enum class Direction: int8_t {
  FORWARD  =  1,
  BACKWARD = -1
};
Direction direction = Direction::BACKWARD;


Stepper stepper(6, 7);
RotateControl rotateController;


volatile bool newTick;
void tick() {
  newTick = true;
}


elapsedMillis elapsedTime = 0;


void setup() { 
  Serial.begin(115200);
  while (!Serial) { }

  stepper.setMaxSpeed(maxSpeed);
  stepper.setAcceleration(maxAcceleration);
  stepper.setPosition(0);
  rotateController.rotateAsync(stepper);
  rotateController.overrideSpeed(0.0f);
  
  newTick = false;
  Timer1.initialize(printInterval);
  Timer1.attachInterrupt(tick);

  elapsedTime = toggleDirectionInterval / 2;
}


void loop() {
  if (elapsedTime >= toggleDirectionInterval) {
    
    elapsedTime -= toggleDirectionInterval;

    switch (direction) {
      case Direction::FORWARD:
        targetSpeed = forwardSpeed;
        direction = Direction::BACKWARD;
        break;
      case Direction::BACKWARD:
        targetSpeed = -backwardSpeed;
        direction = Direction::FORWARD;
        break;
    }
    rotateController.overrideSpeed(targetSpeed / static_cast<float>(maxSpeed));
  }

  if (newTick) {
    newTick = false;
    int32_t currentPosition = stepper.getPosition();
    int32_t currentSpeed = rotateController.getCurrentSpeed();
    Serial.printf("%d\t%d\t%d\n", currentPosition, targetSpeed, stepper.dir * currentSpeed);
  }
}

TeensyStep_Freeze

@luni64
Copy link
Owner

luni64 commented Mar 17, 2023

Thanks for analyzing. Even if it doesn't sound likely after that analysis, can you do a quick check if TimerOne generates the issue?(see #111)

@baender
Copy link
Author

baender commented Mar 17, 2023

I replaced TimerOne and interrupt attachment with a standard elapsedMicros and polling for printing (should have done that in the first place). The behaviour is the same as described in this issue, with TeensyStep 2.3.0 it gets frozen, with the small edit of 2.0.0 it works properly.

@luni64
Copy link
Owner

luni64 commented Mar 19, 2023

Thanks for the test. I'm a bit reluctant to change it back since there probably was a reason for the change. I'll have a closer look as soon as I have more time. Let me know if it runs without issues in the long run.

@baender
Copy link
Author

baender commented Mar 19, 2023

Sure. For now we tested the "fix" with our actual application which includes a simple PID controller (only P for now) to control the rotate controller via target position. Under timing conditions that led to a freeze in 2.3.0, it now runs smoothly. So far, we could not observe any side effects.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants