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
283 stars 67 forks source link

0.30.4: - Fix for issue #178: speed does not decelerate but jumps to lower value #183

Closed mgroz closed 1 year ago

mgroz commented 1 year ago

This still might be a problem using a NEMA17 motor with MicroStepDriver.

My setup is as follows:

Trying To:

The stepper driver is set to 3200 steps per revolution. My setup uses 8 nuts on the wheel and I'm trying to generate 92Hz. Based on the above formula, the STEPPER->setSpeedInHz = 36800. My hardware pins are: ENGINE.stepperConnectToPin(6), setDirectionPin(9),setEnablePin(10,false); The software sets setAutoEnable(true). Movements use runForward();stopMove(); For stopping, I also call isStopping() to wait for motor to halt.

Using setAcceleration(5000), I can run 2hz, 52Hz both up and down. I can spin the motor up to 92Hz. The problem occurs when I try stopping at 92 Hz. The motor starts locking up and skipping. I've tried setting the setAcceleration(2000), still have issues.

Am I doing something wrong or is the 0.30.4 still an issue ?

I appreciate anything you can do to help me with this issue.

Thanks

gin66 commented 1 year ago

Could you please make a short sketch, which illustrates the phenomenon and causes the issue in your setup ?

mgroz commented 1 year ago

Thank you so much for getting back to me.

This is a large project so it may be best to describe what I'm using and how the stepper is integrated.

I have a VB.net application communicating to the atmega2560 via the serial port which gets commands in the loop(). It then calls a routine to split the command and parameters apart to perform various functions on the atmega. This is everything from digital,analog,PWM,Freq Meas, Pulse Counting, etc.

To keep things simple, what was running prior to stopping the stepper was a pulse counter using: attachInterrupt(digitalPinToInterrupt(pin), count_pulse, pin_edge);

The VB.net application then sends the command to atmega: detachInterrupt(digitalPinToInterrupt(pulse_counter_interrupt_pin)); Note: other code fetches the pulse count,etc before the detach. At this point, the atmega is strictly running the stepper at the parameters I stated in my last message waiting for another command in the main loop(). My next call from the VB.net app. is to stop the stepper using a wait parameter, see below. All this wait does is run the following (also see code snippet below): STEPPER->stopMove(); //check if we should wait till motor stops if (command_array[array_index + 3] == "TRUE") { while (STEPPER->isStopping()); } USE_SERIAL.println(F("Ok"));

From my understanding of your library, this is a flag that gets set until the motor has stopped. Like I mentioned earlier,

its been working at other lower speed rates. In fact, it consistently accelerates without problem at the fast rate. 90% of the

time the above code works and the motor decelerates just fine. The other 10% is like the motor has received an invalid step

sequence and goes int a grinding speed (humming) then finally stops.

The motor has a very light load so the current acceleration rate of 5000 should not be an issue. I've even swapped out the stepper drive controller but still have the problem. From previous experimentation, if I overstep the motor it’s a problem on both acceleration and de-accleration. In fact, I've ran step rates at 50000, however not over multiple runs to verify intermittency.

Here is a code snippet with the following order of commands to the fault: 1) atmega2560 is reset: //Prep Stepper Engine. Note: it gets created in process_command() <-STEPPER,SET_UP,6,9,10 FastAccelStepperEngine ENGINE = FastAccelStepperEngine(); FastAccelStepper* STEPPER = NULL; 2) Serial commands sent from VB.net app. to SET_UP stepper response = Send_Serial_Command(commport, "STEPPER,SET_UP,6,9,10", Utility.Commands.Yes, calling_function) response = Send_Serial_Command(commport, "STEPPER,SET_ACCEL,5000", Utility.Commands.Yes, calling_function) response = Send_Serial_Command(commport, "STEPPER,SET_SPEED," + speed.ToString(), Utility.Commands.Yes, calling_function) response = Send_Serial_Command(commport, "STEPPER,MOVE," + dir_str, Utility.Commands.Yes, calling_function) Note: at this point, the stepper accelerates up to speed just fine... 3) While the stepper is running, I issue the command to perform a pulse count as stated above. As noted above, the interrupt gets detached before stopping the stepper. 4) Now I perform the STOP command and ask atmega code to wait until the stepper has stopped: response = Send_Serial_Command(commport, "STEPPER,STOP,STOP_MOVE," + wait_str, Utility.Commands.Yes, calling_function)

I even tried using a delay between calls to isStopping(). Since the stepper is running via hardware timers, this was a long shot and did not work. It’s like the stepper, during deceleration, can intermittently output the wrong pulse frequency or a condition maybe with direction/enable that the controller does not like to see.

I've even ran the acceleration at 2000 and still had this intermittency. You should be able to repeat the steps I've stated and

see if the library outputs the incorrect rate, etc. You may have to run this in a loop as well due to intermittency.

Even a work around would help at this point. Thanks

THE BELOW IS C++ ON ATMEGA DEALING WITH STEPPER LIBRARY:

                }//THIS IS FOR SETTING UP A STEPPER MOTOR OBJECT
                else if ((command_array[array_index] == "STEPPER") && (command_array[array_index + 1] == "SET_UP"))
                {              //make sure digital pin is valid for PULSE_PIN (step pin)
                                stepPinStepper = command_array[array_index + 2].toInt();
                                if (stepPinStepper == 6)
                                {   //make sure digital pin is valid for DIRECTION_PIN
                                                dirPinStepper = command_array[array_index + 3].toInt();
                                                if (dirPinStepper >= 2 && dirPinStepper <= 53)
                                                {   //make sure digital pin is valid for ENABLE_PIN
                                                                enablePinStepper = command_array[array_index + 4].toInt();
                                                                if (enablePinStepper >= 2 && enablePinStepper <= 53)
                                                                {   //make sure STEPPER was not already created. Note: the step pin cannot be changed after creation
                                                                                if (STEPPER == NULL)
                                                                                {
                                                                                    //all is good so initialize & create stepper class
                                                                                              ENGINE.init();
                                                                                               STEPPER = ENGINE.stepperConnectToPin(stepPinStepper);
                                                                                }
                                                                                //make sure stepper is valid and if so, set the DIR & ENA pins
                                                                                if (STEPPER != NULL)
                                                                                {
                                                                                                //make sure stepper has stopped of the engine can get confused since we are changing its control signals
                                                                                                STEPPER->stopMove();
                                                                                                STEPPER->setDirectionPin(dirPinStepper);
                                                                                                //set enable pin and invert polarity (high=enable motor)
                                                                                                STEPPER->setEnablePin(enablePinStepper,false);
                                                                                                //set stepper to control ENABLE pin automatically, reduces heat
                                                                                                STEPPER->setAutoEnable(true);
                                                                                                USE_SERIAL.println(F("Ok"));
                                                                                }
                                                                                else
                                                                                                USE_SERIAL.println(F("Cannot Create Stepper Object"));
                                                                }
                                                                else
                                                                                USE_SERIAL.println(F("ENABLE_PIN Pin Not Valid"));
                                                }
                                                else
                                                                USE_SERIAL.println(F("DIRECTION_PIN Pin Not Valid"));
                                }
                                else
                                                USE_SERIAL.println(F("PULSE_PIN Not Valid"));
                }//THIS SETS THE ACCELERATION PARAMETER FOR THE STEPPER
                else if ((command_array[array_index] == "STEPPER") && (command_array[array_index + 1] == "SET_ACCEL"))
                {              //make sure STEPPER ENGINE has been created
                                if (STEPPER != NULL)
                                {
                                                //set acceleration i.e. steps per sec per sec
                                                STEPPER->setAcceleration(command_array[array_index + 2].toInt());
                                                USE_SERIAL.println(F("Ok"));
                                }
                                else
                                                USE_SERIAL.println(F("Stepper Has Not Been Initialized"));
                }//THIS SETS THE STEP SPEED IN HZ
                else if ((command_array[array_index] == "STEPPER") && (command_array[array_index + 1] == "SET_SPEED"))
                {              //make sure STEPPER ENGINE has been created
                                if (STEPPER != NULL)
                                {
                                                //set top stepper speed in steps per second
                                                STEPPER->setSpeedInHz(command_array[array_index + 2].toInt());
                                                USE_SERIAL.println(F("Ok"));
                                }
                               else
                                                USE_SERIAL.println(F("Stepper Has Not Been Initialized"));
                }//THIS WILL MOVE THE STEPPER MOTOR THE NUMBER OF STEPS PASSED IN MOVE_STEPS
                else if ((command_array[array_index] == "STEPPER") && (command_array[array_index + 1] == "MOVE_STEPS"))
                {              //make sure STEPPER ENGINE has been created
                                if (STEPPER != NULL)
                                {
                                                //move relative to current position this many steps (pos=cw, neg=ccw).
                                                STEPPER->move(command_array[array_index + 2].toInt());
                                                USE_SERIAL.println(F("Ok"));
                                }              
                                else
                                                USE_SERIAL.println(F("Stepper Has Not Been Initialized"));
                }//THIS WILL MOVE THE STEPPER IN THE FORWARD OR BACKWARD DIRECTION CONTINUOUSLY
                else if ((command_array[array_index] == "STEPPER") && (command_array[array_index + 1] == "MOVE"))
                {              //make sure STEPPER ENGINE has been created
                                if (STEPPER != NULL)
                                {
                                                if (command_array[array_index + 2] == "FORWARD")
                                                {
                                                                STEPPER->runForward();
                                                                USE_SERIAL.println(F("Ok"));
                                                }
                                                else if (command_array[array_index + 2] == "BACKWARD")
                                                {
                                                                STEPPER->runBackward();
                                                                USE_SERIAL.println(F("Ok"));
                                                }
                                                else
                                                                USE_SERIAL.println(F("DIRECTION is incorrect"));
                                }
                                else
                                                USE_SERIAL.println(F("Stepper Has Not Been Initialized"));

               }//THIS WILL STOP THE STEPPER MOTOR USING DE-ACCELERATION OR IMMEDIATELY
                else if ((command_array[array_index] == "STEPPER") && (command_array[array_index + 1] == "STOP"))
                {              //make sure STEPPER ENGINE has been created
                                if (STEPPER != NULL)
                               {   //this will stop the motor using the acceleration parameter
                                                if (command_array[array_index + 2] == "STOP_MOVE")
                                                {
                                                                STEPPER->stopMove();
                                                                //check if we should wait till motor stops
                                                                if (command_array[array_index + 3] == "TRUE")
                                                                {
                                                                                while (STEPPER->isStopping());
                                                                }
                                                                USE_SERIAL.println(F("Ok"));
                                                }
                                                else if (command_array[array_index + 2] == "FORCE_STOP")
                                                {   //this will stop the motor immediately
                                                                STEPPER->forceStop();
                                                                USE_SERIAL.println(F("Ok"));
                                                }
                                                else
                                                                USE_SERIAL.println(F("STOP MODE is incorrect"));
                                }
                                else
                                                USE_SERIAL.println(F("Stepper Has Not Been Initialized"));

From: gin66 @.> Sent: Wednesday, June 21, 2023 3:27 PM To: gin66/FastAccelStepper @.> Cc: mgroz @.>; Author @.> Subject: Re: [gin66/FastAccelStepper] 0.30.4: - Fix for issue #178: speed does not decelerate but jumps to lower value (Issue #183)

Could you please make a short sketch, which illustrates the phenomenon and causes the issue in your setup ?

— Reply to this email directly, view it on GitHub https://github.com/gin66/FastAccelStepper/issues/183#issuecomment-1601624063 , or unsubscribe https://github.com/notifications/unsubscribe-auth/A4RUL64YXJ26TY24REUWVVLXMNKKPANCNFSM6AAAAAAZN6ANWQ . You are receiving this because you authored the thread. https://github.com/notifications/beacon/A4RUL65Q5FTNJZTWNKOJ7JLXMNKKPA5CNFSM6AAAAAAZN6ANWSWGG33NNVSW45C7OR4XAZNMJFZXG5LFINXW23LFNZ2KUY3PNVWWK3TUL5UWJTS7O3L76.gif Message ID: @. @.> >

mgroz commented 1 year ago

Would this work around be valid: Motor Running At Full Speed 1) applySpeedAcceleration() <-set acceleration to a low value like 500 - 1000 2) issue another move() <-delay some period of time 3) applySpeedAcceleration() <-set acceleration back to 5000 4) issue another move() immediately followed by stopMove()

Also, the stepper motor is: Usongshine Nema 17 Stepper Motor 17HS4401S, 42BYGH: https://a.co/d/86pCO5O 1.8 Degree, maximum no load starting >= 1900 pulses per second 1.5A per phase

gin66 commented 1 year ago

Thanks for the description. Based on it, I have set up a test case for 2560 and apparently there is an issue. Will look into the root cause during the weekend

mgroz commented 1 year ago

Thank you so much for looking into this. It's a wonderful package for driving stepper motors. Really appreciate your efforts!!!

gin66 commented 1 year ago

OK. after some more analysis, I have identified an unrelated issue: If the stepper is in keep running mode and then move() is called, the calculated target position was nonsense. Now it uses the queue end position as reference for the relative move().

Unfortunately, this does not explain your issue.

So I am wondering, if the error is related to interrupt management. Running the stepper at 38500 steps/s means an interrupt every 27us. This would mean, the acceleration is not really related to the issue. Perhaps the pulse counter interrupt/setup/deinit prevents interrupt processing in time, or receiving bytes from the serial interface. Can you eventually not use the pulse counter interrupt or try to find a relation between stepper issue and issueing a serial command ?

mgroz commented 1 year ago

Thanks for looking further into this.

I've also changed the way I'm looking at the current stepper motor acceleration. Using this new method, I did find it interesting that I had to have a healthy delay to ensure the flag was changed after issuing the Stop() command, see code.

Just to be clear, the interrupt routine for counting pulses was disabled before calling the STOP code below. If you look at the code, it's really a blocking routine as it waits for this flag to change states. Other than other interrupts, the main Loop() is not run checking for commands. In addition, the VB.net code is froze waiting for the "Ok" from this routine so there is no other serial activity.

It's a tough problem since it runs just fine most of the time. I'm going to see if the above changes make a difference. If not, I might bump up the peak current from the driver to motor to help minimize slippage/over-stepping if that is a variable. My plan is to stress test it by writing a quick routine to issue FORWARD then STOP commands in a loop. I'll also completely perform no pulse counting then keep pulse counting enabled.

            if (command_array[array_index + 2] == "STOP_MOVE")
            {
                STEPPER->stopMove();
                //check if we should wait till motor stops
                if (command_array[array_index + 3] == "TRUE")
                {
                    //this delay is critical to ensure stopMove() has time to change RAMP mode. If not
                    //done, it will blow straight through.
                    wait_ms(100);
                    while ((STEPPER->rampState() & RAMP_STATE_DECELERATE) == RAMP_STATE_DECELERATE);
                    //old method of stopping
                    //while (STEPPER->isStopping());
                }
                USE_SERIAL.println(F("Ok"));
            }
gin66 commented 1 year ago

Thanks for looking into the possibility for long interrupt blockage. If this is not the cause, then I am currently out of ideas. At long as I have no way to reproduce it, I have nothing to work on. So thanks for your support to getting this clarified.

stopmove() only sets a flag, which is then evaluated by the cyclic stepper task. This means, it can take up to 4ms until that flag is processed and the ramp state is changing. On the other hand isStopping() takes this flag into consideration and returns true, until ramp state switches to IDLE or another call like move(), moveTo().... takes place. Was there any problem, why you have changed to rampState().

BTW: Could be an option to offer a blocking variant void stopMove(bool block=false) !?

mgroz commented 1 year ago

Thanks for the explanation on the inner method of how you set/evaluate these.

As for why I changed the approach, strictly to try a different method. In addition, I wanted to add a blocking function when spinning up the motor. My VB.net application needs to ensure motor is a full speed before making measurements. On the problem-solving side, I'm very limited to what physically can be changed at this point.

What method would you suggest for taking an incremental de-acceleration approach. Is there a way to dynamically change the acceleration value in steps till the motor spun down to a certain speed then set value back up to full and let it reach a stop? Once again, I'm thinking out of the box.

As for the bool blocking parameter, that would be great!! It would be nice to have it on both spinning up and stopping.

Thanks again and I'll update when I get more results...

mgroz commented 1 year ago

Well it looks like the pulse_count() routine is causing the stepper pulse to get out of phase with the motor. Inside that routine, I had glitch protection which was adding too much time inside the interrupt. This processor does not have preempt interrupt handling so I dropped the glitch readback and its very stable. If someone wants to re-produce this problem, just spin up the motor and disconnect/connect the stepper pulse line.

Here is what I did in code:

void count_pulse()
{
    if (COUNTING_PULSES) 
    {
        //this is to be used strictly on a clean signal i.e. from a comparator ckt with hysteresis.
        //if not, un-comment the code below
        PULSE_COUNT++;
        //if (digitalRead(PULSE_COUNTER_INTERRUPT_PIN) == digitalRead(PULSE_COUNTER_INTERRUPT_PIN))
        //{
        //  PULSE_COUNT++;
        //}
    }
}

If you're going to run at high rates, outside interrupts have to be limited.

Thanks

gin66 commented 1 year ago

Wow. Great finding and root cause analysis. I will add this to the Lessons Learned section to point this out for future app developers.

BTW: For spinning up aka starting a move, there exists already blocking versions.

int8_t move(int32_t move, bool blocking = false);
int8_t moveTo(int32_t position, bool blocking = false);

Only runForward(), runBackward() and stopMove() have no blocking parameter. Should be easy to add this feature.

mgroz commented 1 year ago

Thanks for your help.

Having blocking abilities on: runForward(), runBackward() and stopMove() would be great. For my applications, the motor will always be running.

gin66 commented 1 year ago

Just have seen, that a blocking runForward() and runBackward() would never return…. So only stopMove() makes sense