Git Product home page Git Product logo

gin66 / fastaccelstepper Goto Github PK

View Code? Open in Web Editor NEW
300.0 20.0 69.0 2.21 MB

A high speed stepper library for Atmega 168/328p (nano), Atmega32u4, Atmega 2560, ESP32, ESP32S2, ESP32S3, ESP32C3, ESP32C6 and Atmel SAM Due

License: MIT License

C++ 76.43% C 10.04% Makefile 9.87% Shell 2.74% Awk 0.87% CMake 0.03% Nix 0.03%
arduino atmega328 nano acceleration driver-ic highspeed tested stepper motor a4988

fastaccelstepper's Introduction

BE AWARE: ARDUINO LIBRARY MANAGER IS BROKEN AND 0.29.x/0.30.x with x>0 do not show.

No issue with platformio. Check the related issue for the arduino library manager

arduino-library-badge

FastAccelStepper

GitHub tag PlatformIO Registry arduino-library-badge

Run tests Simvar tests

Matrix build for arduino using platformio (esp32, esp32c3, atmega328,...)

Build examples

Matrix build for espidf using platformio

Build espidf

Build for esp32 with tasmota

V2_0_15

Arduino and esp32

Arduino core v3.0.x are using esp-idf v5.0 up to v5.1 and FastAccelStepper will fail to compile.

Arduino core 3.1.0 will support ESP-IDF V5.3.0 (based on RC1)

Overview

This is a high speed alternative for the AccelStepper library. Supported are avr (ATmega 168/328/P, ATmega2560, ATmega32u4), esp32, esp32s2, esp32s3, esp32c3, esp32c6 and atmelsam due.

The stepper motors should be connected via a driver IC (like A4988) with a 1, 2 or 3-wire connection:

  • Step Signal
    • avr atmega168/328/p: only Pin 9 and 10.
    • avr atmega32u4: only Pin 9, 10 and 11.
    • avr atmega2560: only Pin 6, 7 and 8. On platformio, this can be changed to other triples: 11/12/13 Timer 1, 5/2/3 Timer 3 or 46/45/44 Timer 5 with FAS_TIMER_MODULE setting.
    • esp32: This can be any output capable port pin.
    • atmel sam due: This can be one of each group of pins: 34/67/74/35, 17/36/72/37/42, 40/64/69/41, 9, 8/44, 7/45, 6
    • Step should be done on transition Low to High. High time will be only a few us. On esp32 the high time is for slow speed fixed to ~2ms and high speed to 50% duty cycle
  • Direction Signal (optional)
    • This can be any output capable port pin.
    • Position counting up on direction pin high or low, as per optional parameter to setDirectionPin(). Default is high.
    • With external callback on esp32 derivates, even shift register outputs can be used
  • Enable Signal (optional)
    • This can be any output capable port pin.
    • Stepper will be enabled on pin high or low, as per optional parameter to setEnablePin(). Default is low.
    • With external callback, even shift register outputs can be used

FastAccelStepper offers the following features:

  • 1-pin operation for e.g. peristaltic pump => only positive move
  • 2-pin operation for e.g. axis control
  • 3-pin operation to reduce power dissipation of driver/stepper
  • Lower limit of 260s per step @ 16MHz aka one step every four minute (esp32/avr), 198s for sam due
  • fully interrupt/task driven - no periodic function to be called from application loop
  • supports acceleration and deceleration with per stepper max speed/acceleration
  • Allows the motor to continuously run in the current direction until stopMove() is called.
  • speed/acceleration can be varied while stepper is running (call to functions move or moveTo is needed in order to apply the new values)
  • Constant acceleration control: In this mode the motor can be controled by acceleration values and with acceleration=0 will keep current speed
  • Linear acceleration increase from/to standstill using cubic speed function - configurable by setLinearAcceleration()
  • Jump start from standstill - configurable by setJumpStart()
  • Auto enable mode: stepper motor is enabled before movement and disabled afterwards with configurable delays
  • Enable pins can be shared between motors
  • Direction pins can be shared between motors
  • Configurable delay between direction change and following step
  • External callback function can be used to drive the enable pins (e.g. connected to shift register) and, only esp32 derivates: the direction pins
  • No float calculation (poor man float: use log2 representation in range -64..64 with 16bit integer representation and 1/512th resolution)
  • Provide API to each steppers' command queue. Those commands are tied to timer ticks aka the CPU frequency!
  • Command queue can be filled with commands and then started. This allows near synchronous start of several steppers for multi axis applications.

Star History

Star History Chart

General behaviour:

  • The desired end position to move to is set by calls to moveTo() and move()
  • The desired end position is in case of moveTo() given as absolute position
  • For move() the delta is added to the latest desired end position
  • The stepper tries to reach the given desired end position as fast as possible with adherence to acceleration/deceleration
  • If the stepper is e.g. running towards position 1000 and moveTo(0) is called at position 500, then the stepper will
    1. decelerate, which means it will overshoot position 500
    2. stop and accelerate towards 0
    3. eventually coast for a while and then decelerate
    4. stop
  • The stepper position is a 32bit integer variable, which wraps around for continuous movement. Example:
    • Assume counting up turns stepper clockwise, and counting down, anti-clockwise.
    • Current position is -2.000.000.000, move to 2.000.000.000.
    • Apparently the position has to count up, and count should run clockwise.
    • Implementation is done via difference of 32bit signed numbers, which can overflow (being legal).
    • The calculation is then: 2.000.000.000 - (-2.000.000.000) = 4.000.000.000
    • But 4.000.000.000 interpreted as signed 32bit is -294.967.296 => count down, turn anti-clockwise Means the position will count:
		-2.000.000.000
		-2.000.000.001
		-2.000.000.002
			:
		-2.147.483.647
		-2.147.483.648
		 2.147.483.647
		 2.147.483.646
		 2.147.483.645
			:
		 2.000.000.000

Comments to pin sharing:

  • Enable pin sharing: the common pin will be enabled for as long as one motor is running + delay off. Every motor will adhere to its auto enable delay, even if other motors already have enabled the pin.
  • Direction pin sharing: The direction pin will be exclusively driven by one motor. If one motor is operating, another motor will wait until the direction pin comes available

AVR ATMega 168/168P/328/328P

  • allows up to 50000 generated steps per second for single stepper operation, 37000 for dual stepper
  • supports up to two stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Uses F_CPU Macro for the relation tick value to time, so it should now not be limited to 16 MHz CPU frequency (untested)
  • Steppers' command queue depth: 16

AVR ATMega 32u4

  • allows up to 50000 generated steps per second for single stepper operation, 37000 for dual stepper and 20000 for three steppers
  • supports up to three stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Uses F_CPU Macro for the relation tick value to time, so it should now not be limited to 16 MHz CPU frequency (untested)
  • Steppers' command queue depth: 16

AVR ATMega 2560

  • allows up to 50000 generated steps per second for single stepper operation, 37000 for dual stepper and 20000 for three steppers
  • supports up to three stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Uses F_CPU Macro for the relation tick value to time, so it should now not be limited to 16 MHz CPU frequency (untested)
  • Steppers' command queue depth: 16
  • This device has four 16 bit timers, so extension up to 12 steppers should be possible (not implemented)

ESP32

ESP-IDF version 4.x.y:

  • allows up to 200000 generated steps per second
  • supports up to 14 stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

ESP-IDF version >=5.3.0:

  • allows up to 200000 generated steps per second
  • supports up to 8 stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

ESP32S2

  • reported to work
  • allows up to 200000 generated steps per second ?
  • supports up to four stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

ESP32S3

ESP-IDF version 4.x.y:

  • allows up to 200000 generated steps per second ?
  • supports up to eight stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

ESP-IDF version >=5.3.0:

  • allows up to 200000 generated steps per second ?
  • supports up to four stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

ESP32C3

  • allows up to 200000 generated steps per second ?
  • supports up to two stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

ESP32C6

  • only from esp-idf >=v5.3.0
  • allows up to 200000 generated steps per second ?
  • supports up to four stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32
  • untested

Atmel SAM Due

  • allows up to 50000 generated steps per second
  • supports up to six stepper motors using Step/Direction/Enable Control (Direction and Enable is optional)
  • Steppers' command queue depth: 32

Tested with max two stepper motors with 50 kHz step rate by clazarowitz

Usage

The library is in use with A4988, but other driver ICs should work, too.

For the API definition please consult the header file FastAccelStepper.h. Or a generated markdown file

Please check the examples for application and how to use the low level interface. Some info is Issue #86.

The module defines the global variable fas_queue. Do not use or redefine this variable.

Using the high level interface with ramp up/down as in UsageExample.ino.

#include "FastAccelStepper.h"
#include "AVRStepperPins.h" // Only required for AVR controllers

#define dirPinStepper    5
#define enablePinStepper 6
#define stepPinStepper   9

// If using an AVR device use the definitons provided in AVRStepperPins
//    stepPinStepper1A
//
// or even shorter (for 2560 the correct pin on the chosen timer is selected):
//    stepPinStepperA

FastAccelStepperEngine engine = FastAccelStepperEngine();
FastAccelStepper *stepper = NULL;

void setup() {
   engine.init();
   stepper = engine.stepperConnectToPin(stepPinStepper);
   if (stepper) {
      stepper->setDirectionPin(dirPinStepper);
      stepper->setEnablePin(enablePinStepper);
      stepper->setAutoEnable(true);

      stepper->setSpeedInHz(500);       // 500 steps/s
      stepper->setAcceleration(100);    // 100 steps/s²
      stepper->move(1000);
   }
}

void loop() {
}

Few comments to auto enable/disable:

  • If the motor is operated with micro stepping, then the disable/enable will cause the stepper to jump to/from the closest full step position.

  • Some drivers need time to e.g. stabilize voltages until stepping should start. For this the start on delay has been added. See issue #5.

  • The turn off delay is realized in the cyclic task for esp32 or cyclic interrupt for avr. The esp32 task uses 4ms delay, while the avr repeats every ~4 ms at 16 MHz and atmel sam due every 2ms at 21MHz. Thus the turn off delay is a multiple (n>=2) of those period times and actual turning off takes place approx [(n-1)..n] * 4 ms resp. 2ms after the last step.

  • The turn on delay is minimal MIN_CMD_TICKS.

  • More than one stepper can be connected to one auto enable pin. Behaviour is like this:

    1. If stepper #1 needs enable, then it will enable it with its defined on delay time.
    2. If stepper #2, which is connected to same enable pin, starts after stepper one, then it still will wait its defined on delay time and set the enable pin, again (no-op). The stepper #2 is not aware, that another stepper (stepper #1) has enabled the outputs already.
    3. If e.g. stepper #1 stops, then stepper #1's delay off counter is started.
    4. When stepper #1's counter is finished, then the FastAccelStepperEngine will ask all steppers, if they agree to stepper #1's disable request. If stepper #2 is still running, then stepper #2 will not agree and the output will stay enabled.
    5. When stepper #2 stops, then stepper #2's delay off counter is started.
    6. When stepper #2's counter is finished, then the FastAccelStepperEngine will ask all steppers, if they agree to stepper #2's disable request. Stepper #1 agrees, because it is not running. So the engine will call Stepper #2's AND Stepper #1's disableOutputs().

    The library does not consider the case, that Low/High Active enable may be mixed. This means stepper #1 uses the enable pin as High Active and stepper #2 the same pin as Low Active. => This situation will not be identified and will lead to unexpected behaviour

Behind the curtains

AVR ATmega168/328 and Atmega32u4

The timer 1 is used with prescaler 1. With the arduino nano running at 16 MHz, timer overflow interrupts are generated every ~4 ms. This timer overflow interrupt is used for adjusting the speed.

The timer compare unit toggles the step pin from Low to High precisely. The transition High to Low is done in the timer compare interrupt routine, thus the High state is only few us.

After stepper movement is completed, the timer compare unit is disconnected from the step pin. Thus the application could change the state freely, while the stepper is not controlled by this library.

Measurement of the acceleration/deacceleration aka timer overflow interrupt yields: one calculation round needs around 300us. Thus it can keep up with the chosen 10 ms planning ahead time.

AVR ATmega2560

Similar to ATmega328, but instead of timer 1, timer 4 is used.

For users of platformio, the used timer can be changed to either 1, 3, 4 or 5. For e.g. timer module 3 add to platformio.ini under build_flags:

build_flags = -DFAS_TIMER_MODULE=3

or better:

build_flags = -Werror -Wall -DFAS_TIMER_MODULE=3

For arduino users, the same can be done by defining the flag before including the FastAccelStepperEngine.h header (as per info ixil), but apparently to issue #50, this approach does not work for everyone: e.g.

sketch.ino
----------
#include <Arduino.h>
#define FAS_TIMER_MODULE 3
#include <FastAccelStepper.h>
/* ... */

ESP32

ESP-IDF version 4.x.y:

This stepper driver uses mcpwm modules of the esp32: for the first three stepper motors mcpwm0, and mcpwm1 for the steppers four to six. In addition, the pulse counter module is used starting from unit_0 to unit_5. This driver uses the pcnt_isr_service, so unallocated modules can still be used by the application. The mcpwm modules' outputs are fed into the pulse counter by direct gpio-matrix-modification.

For the other stepper motors, the rmt module comes into use.

ESP-IDF version >=5.3.0:

Only rmt module is supported.

All

A note to MIN_CMD_TICKS using mcpwm/pcnt: The current implementation uses one interrupt per command in the command queue. This is much less interrupt rate than for avr. Nevertheless at 200kSteps/s the switch from one command to the next one should be ideally serviced before the next step. This means within 5us. As this cannot be guaranteed, the driver remedies an overrun (at least by design) to deduct the overrun pulses from the next command. The overrun pulses will then be run at the former command's tick rate. For real life stepper application, this should be ok. To be considered for raw access: Do not run many steps at high rate e.g. 200kSteps/s followed by a pause.

What are the differences between mcpwm/pcnt and rmt ?

mcpwm/pcnt rmt
Interrupt rate/stepper one interrupt per command min: one interrupt per command, max: one interrupt per 31 steps at high speed
Required interrupt response at high speed: time between two steps at high speed: time between 31 steps
Module usage 1 or 2 mcpcms, up to 6 channels of pcnt rmt
esp32 notes availabe pcnt modules can be connected no pcnt module used, so can be attached to rmt output as realtime position

If the interrupt load is not an issue, then rmt is the better choice. With rmt the below (multi-axis application) mentioned loss of synchonicity at high speeds can be avoided. The rmt driver is - besides some rmt modules perks - less complex and way more straightforward.

As of now, allocation of steppers on esp32 are: first all 6 mcpwm/pcnt drivers and then the 8 rmt drivers. In future this may be under application control. Starting with 0.29.2, the module can be directly selected on call of stepperConnectToPin(). So the allocation gets more flexible.

One specific note for the rmt: If a direction pin toggle is needed directly after a command with steps, then the driver will add before that direction pin toggle another pause of MIN_CMD_TICKS ticks.

ESP32S2

This stepper driver uses rmt module.

ESP32S3

The ESP32S3's rmt module is similar to esp32c3 with 4 instead of 2 channels and with different register names.

ESP-IDF version 4.x.y:

This stepper driver uses mcpwm/pcnt + rmt modules. Can drive up to 8 motors. Tested with 6 motors (not by me).

ESP-IDF version >=5.3.0:

This stepper driver uses rmt modules. Can drive up to 4 motors.

ESP32C3

This stepper driver uses rmt module and can drive up to 2 motors. Not thoroughly tested, so only experimental support.

ESP32-MINI-1

Compatibility with ESP32-MINI-1: At least mcpwm and pulse counter modules are listed in the datasheet. So there are chances, that this lib works.

Atmel SAM Due

This is supported by clazarowitz

ALL

The used formula is just s = 1/2 * a * t² = v² / (2 a) with s = steps, a = acceleration, v = speed and t = time. In order to determine the speed for a given step, the calculation is v = sqrt(2 * a * s). The performed square root is an 8 bit table lookup using log2/pow2. Sufficient exact for this purpose.

For the linear acceleration from/to standstill the used formula is s = 1/2 * j * t³. The variable j is calculated from acceleration and steps of linear acceleration, which is set by setLinearAcceleration().

The compare interrupt routines use 16bit tick counters, which translates to approx. 4ms. For longer time between pulses, pauses without step output can be added. With this approach the ramp generation supports up to one step per 268s.

The low level command queue for each stepper allows direct speed control - when high level ramp generation is not operating. This allows precise control of the stepper, if the code, generating the commands, can cope with the stepper speed (beware of any Serial.print in your hot path).

The chosen approach has few limitations for esp32. With acceleration = 1 step/s², the maximum speed is approx. 92 kStep/s. The max. supported speed for esp32 will be reachable only with acceleration >= 5 step/s².

Usage for multi-axis applications

For coordinated movement of two or more axis, the current ramp generation will not provide good results. The planning of steps needs to take into consideration max.speed/acceleration of all steppers and eventually the net speed/acceleration of the resulting movement together with its restrictions. Nice example of multi-axis forward planning can be found within the marlin-project. If this kind of multi-dimensional planning is used, then FastAccelStepper is a good solution to execute the raw commands (without ramp generation) with near-synchronous start of involved steppers. With the tick-exact execution of commands, the synchronization will not be lost as long as the command queues are not running out of commands. And for esp32, second requirement is, that the interrupts can be serviced on time (no pulses issued with previous command's pulse period time)

To keep up the synchronization of two steppers please keep in mind:

  • The stepper queue will on initial start, if configured, add pauses to the command queue to implement enable delay. => Perhaps best to not use enable on delay
  • If the stepper is configured for delays for direction change, then one pause is added to the command queue for each direction change together with a step. => Execute direction change together with a pause or do not configure direction change delay

Note for esp32 rmt driver:

  • Due to the inner implementation, there has been the need to introduce pauses e.g. before a direction change. So the tick-exact execution of commands cannot be assumed, if during command generation pauses before/after dir changes are not generated by the application.

TODO

See project

Arduino

Arduino library manager log

PLATFORMIO

Library on platformio

If you prefer platformio and you are running Linux, then platformio version of the examples are created by executing

ci/build-platformio.sh

This will create a directory pio_dirs, which contains all examples. Can be executed by e.g.

cd pio_dirs/StepperDemo
pio run -e avr --target upload --upload-port /dev/ttyUSB0

ESP-IDF

A CMakeLists.txt is provided to use FastAccelStepper as an ESP-IDF component. Clone it into the components/ directory in the root of your project and build as usual. You must have Arduino available as a component. See this for instructions on how to set that up. Tested as ESP-IDF component on PlatformIO Espressif32 Platform v3.3.2.

For any questions/support please contact gagank1, as I do not use esp-idf

TEST STRATEGY

The library is tested with different kind of tests:

  • PC only (sub folder ./tests/pc_based)

    These tests focussing primarily the ramp generator and part of the API

  • simavr based for avr (sub folder ./tests/simavr_based)

    The simavr is an excellent simulator for avr microcontrollers. This allows to check the avr implementation thoroughly: number of steps generated, virtual stepper position and even timing. Tested code is mainly the StepperDemo, which gets fed in a one line sequence of commands to execute. These tests are focused on avr, but help to check the whole library code, used by esp32, too.

  • esp32 tests with another pulse counter attached (e.g. test_seq_08 in StepperDemo)

    The FastAccelStepper-API supports to attach another free pulse counter to a stepper's step and dir pins. This counter counts in the range of -16383 to 16383 with wrap around to 0. The test condition is, that the library's view of the position should match the independently counted one. These tests are still evolving

  • Test for pulse generation using examples/Pulses

    This has been intensively used to debug the esp32 ISR code

  • esp32 hw tests

    These tests live under sub folder ./tests/esp32_hw_based

  • manual tests using examples/StepperDemo

    These are unstructured tests with listening to the motor and observing the behavior

Test sequences from StepperDemo

Short info, what the test sequences, embedded in StepperDemo in the test mode, do:

  • 01 - Run the stepper like a clock for one minute
  • 02 - Run the stepper towards positive position and back to zero repeatedly
  • 03/04 - same like 02, both different speed/acceleration
  • 05 - Perform 800 times a single step and then 800 steps back in one command
  • 06 - Run 32000 steps with speed changes every 100ms in order to reproduce issue #24

All those tests have no internal test passed/failed criteria. Those are used for automated tests with ./tests/simavr_based and ./tests/esp32_hw_based. The test pass criteria are: They should run smoothly without hiccups and return to start position.

  • 07 - measures timing of several moveByAcceleration(). Should stop at position zero. (should be started from position 0).
  • 08 - is an endless running test to check on esp32, if the generated pulses are successfully counted by a second pulse counter. The moves should be all executed in one second with alternating direction and varying speed/acceleration
  • 09 - is an endless running test with starting a ramp with random speed/acceleration/direction, which after 1s is stopped with forceStopAndNewPosition(). It contains no internal test criteria, but looking at the log, the match of generated and sent pulses can be checked. And the needed steps for a forceStopAndNewPosition() can be derived out of this
  • 10 - runs the stepper forward and every 200 ms changes speed with increasing positive speed deltas and then decreasing negative speed deltas.
  • 11 - runs the stepper to position 1000000 and back to 0. This tests, if getCurrentPosition() is counting monotonously up or down respectively.

CHANGELOG

See changelog

ISSUES

  • There is an issue with the esp32 mcpwm: as soon as the mcpwm timer is running, on every cycle an interrupt is serviced - even though no interrupt is enabled. If several steppers are running at high step rate, the interrupt load for this nonsense interrupt could be quite high for the CPU. Need further investigation, but till now haven't found the root cause.
  • Compilation using esp-idf 4.4 will yield a deprecation warning for mcpwm_isr_register(). This has been raised as issue at espressif
  • framework-arduinoespressif32 @ 3.10006.210326 and later will lead to compile error for esp32, if using compiler options -Werror -Wall !!! The problem can be circumvented by applying -Wno-error=incompatible-pointer-types

Error investigation

In case the stepper does not run smoothly, then StepperDemo contains commands to simulate two type of error causes. For avr the commands are r and e. For esp32 only e can be used.

  • r: The digitalRead() of arduino is a fancy implementation, which checks, if the pin being read is connected to a timer to generate PWM and if yes, turns this off (actually IMHO a broken implementation: only 1 of the needed 2 bits are cleared, and the activation by force compare is missing). As FastAccelStepper controls the step pin, the digitalRead can disturb the step pin (even though I have expected step loss, only difference in noise can be heard). The error simulation in StepperDemo reads the pins in the main loop(), thus the symptom occurs quite reliably.
  • e: This blocks repeatedly interrupts for ~100us during 64ms out of 256ms. On AVR to see this problem popping up, the stepper rate has to be <~106 us (avr, one stepper running). >~106us it runs quite smoothly. The 106us = 100us block + ~6us ISR runtime. For ESP32 this has no effect.

For avr: cause of long interrupt being blocked can be e.g.:

  • long section of codes between noInterrupts()/interrupts() in the application (or used libraries)
  • long interrupt service routines in the application (or used libraries).
  • port interrupts connected to noisy/bouncy switches causing bursts of interrupts

Especially in interrupt service routines, the digitalRead()/digitalWrite() must be avoided. Alternative solution is described e.g. here: blog, or digitalWriteFast, or fast versions.

This feature of StepperDemo allows to compare non-smooth running stepper in an application with these error types.

Lessons Learned

  • Spent more than half a day debugging the esp32-code, till I have found out, that just the cable to the stepper was broken.
  • In one setup, operating A4988 without microsteps has led to erratic behaviour at some specific low speed (erratic means step forward/backward, while DIR is kept low). No issue with 16 microstep. These two youtube videos show similar behavior: hard disc stepper and axes movement
  • The pulse counters in esp32 have several comparators to trigger interrupts. What the documentation does not mention: All those reference values are only forwarded to the actual comparator on pulse counter reset. Thus the pulse counters cannot be used as lower 16bit of the position, unfortunately.
  • The issue #60 was raised due to wrong position on negative moves with esp32. Apparently the issue was with proper ground and/or power lines to the stepper driver. If similar issue is encountered, please check on this issue
  • ESP32C3: USBSerial works only under Arduino IDE. platformio support for USBSerial is missing

3rd party videos in action

Found on youtube:

As mentioned by kthod861 in Issue #110:

Contribution

  • Thanks ixil for pull request (#19) for ATmega2560
  • Thanks gagank1 for esp-idf integration by adding CMakeLists.txt (#81)
  • Thanks clazarowitz for the amazing atmel sam due port (#82)
  • Thanks HeldeReis for the awesome ESP32-S3 port (#162)
  • Thanks DaAwesomeP for the extension to ATmega 168/168P/328 (#179)
  • Thanks turley for the patch for missing _stepper_cnt initialization (#204)
  • Thanks GarmischWg for adding rmt-support to ESP32-S3 (#225)
  • Thanks SHWotever for avr patch to fix missing direction pin toggle (#252)
  • Thanks HalfVoxel for pull requests (#270) and (#271): improved doc and missing parenthesis in preprocessor macros

fastaccelstepper's People

Contributors

clazarowitz avatar daawesomep avatar dmbuck32 avatar gagank1 avatar garmischwg avatar gin66 avatar halfvoxel avatar heldereis avatar ixil avatar justinong avatar shwotever avatar turley avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

fastaccelstepper's Issues

Test sequence lead to motor not moving

Start test sequence t M1 02 R. While motor is running, issue 02

Result is, that motor is stuck in RED state. Issuance of another 02 resumes function:

[00:42:22:431] Select stepper 1
[00:42:22:433] Select test_seq_02
[00:42:22:434] Run tests
[00:42:22:435] M1: @0 M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:22:523] M1: @1 => 0 QueueEnd=0/22400us MANU M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:22:623] M1: @1 => 0 QueueEnd=0/22400us MANU M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:22:723] M1: @4 => 0 QueueEnd=3/11200us ACC   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:22:823] M1: @3 => 7 QueueEnd=4/11200us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:22:923] M1: @3 => 0 QueueEnd=3/11200us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:023] M1: @4 => 10 QueueEnd=5/9984us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:123] M1: @10 => 0 QueueEnd=9/15808us ACC   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:223] M1: @1 => 0 QueueEnd=1/15808us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:323] M1: @8 => 13 QueueEnd=9/9984us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:423] M1: @11 => 0 QueueEnd=9/9088us ACC   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:523] M1: @1 => 0 QueueEnd=1/15808us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:623] M1: @9 => 17 QueueEnd=10/7904us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:723] M1: @17 => 0 QueueEnd=17/0us ACC   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:770] Select test_seq_02
[00:42:23:771] Run tests
[00:42:23:823] M1: @6 => 1 QueueEnd=5/11200us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:23:923] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:023] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:123] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:223] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:323] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:423] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:523] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:623] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 
[00:42:24:723] M1: @1 => 0 QueueEnd=1/0us RED   M2: @0 M3: @0 M4: @0 M5: @0 M6: @0 

Stepper is not running smooth at slower rpm

When comparing the stepper motor movement between Arduino Nano using the Accelstepper library and the use of ESP32 with the FastAccelStepper library the motor does not run as smooth with the FastAccelStepper library. Is this because this library is optimized for use with faster speeds? We plan to use speeds between 1-5rpm.

Compiler flag for other Timers

Hello, I've been using the library for a project at my Uni - and forked it to so I can use the TIMER4 on a MEGA2560. At the moment it is only functionally I just use sed -i -f regexes.sed ./src/*ISR_avr.cpp to do so. See ixil/FastAccelStepper. (The other difference were just when I was testing it).

Would you be interested/would it be possible to use some preprocessor magic (or better, modern c++) so I do not need to follow your fork?
Thanks for the useful library

How can we use library without setAcceleration?

Hi Gin66,
The motor does not run without setAcceleration defined but we do not require acceleration for our project.
Is this set acceleration required?
What is the maximum value we can set the acceleration to so the motor run immediately to the desired speed (1 to 3rev/min)?
We are trying to run the motor precisely 1 revolution in 60seconds, at a very low rpm and we find that there is very small discrepancy (0.1degrees) error with acceleration set so we are trying to remove the acceleration as a possible source of error.

Glitches at some speeds

Hi,
Thank you very much for this code. I am a newbie. I am testing it on a Clearpath motor:
https://www.teknic.com/model-info/CPM-SDSK-N0563P-RLN/?model_voltage=230VAC3ph .
It has integrated power supply + driver; it accepts standard step/dir or Quad A/B inputs.

I'm using an Arduino Uno 16bit, and attached a digital encoder knob.
The code takes speed commands from the knob and from monitor input.
The motor currently runs at 1000 steps/rev. I am testing at 0-1000rpm.
Motor accelerates to various speeds and reverses elegantly with decel/accel as commanded.
Knob is set to 20rpm increments per tick (count).

Problem: When adjusting speed with knob, at a few speed transitions the motor jolts (glitches) but recovers; motor software MSP warns "torque saturation" condition. Perhaps a rapid stop/start event? Something in the frequency timing comes to mind, but I have no experience.

Examples (at 1000 steps/rev):
Encoder cnt: 27, from 520--540rpm, speedInUs: 111
Encoder cnt: 37, from 720--740rpm, speedInUs: 81
Encoder cnt: 47, from 920--940rpm, speedInUs: 64

Tested: In MSP software, I changed the steps per rev from 1000 to 4000: there still were glitches but at different speeds than before.

I would like to know if someone else has experienced such glitches? And what may be the cause? Thanks.

Using setSpeed() quickly while the stepper is moving causes position loss/incorrect position

(I am using a TTGO T-Display ESP32 and a TMC5160 SilentStepStick v1.5)

Below is the relevant code that triggers the issue; it just moves the stepper back and forth between 0 and a set position "StepsToNext" when I have a button pressed (the code is in the main loop). When "UseSpeedSwitcher" is on, it changes the speed every 100 milliseconds which causes the position loss. When the speed isn't changed, the stepper returns to the correct position each time.

if (analogRead(BUTTON_2) < 1000)
{
  if(!B2Pressed)
    Serial.println("b2 pressed!");
  B2Pressed = true;
  if (millis() > LastMoveToMillis + TimeToNext*1000)
  {
    LastMoveToMillis = millis();
    Serial.println("movespeedmicros: " + String(MoveSpeedMicros));
    Serial.println("movespeed: " + String(MoveSpeed));
    Serial.println("movespeedMax: " + String(MoveSpeedMax));
    MovingToZero = !MovingToZero;
    if (MovingToZero)
    {
      FAS->moveTo(0);
    }
    else
    {
      FAS->moveTo(StepsToNext);
    }
  }
  if (millis() > LastSpeedSwitchMillis + 100 && UseSpeedSwitcher)
  {
    LastSpeedSwitchMillis = millis();
    SwitchedSpeed = !SwitchedSpeed;
    SpeedSwitchedTimes++;
    if (SwitchedSpeed)
      FAS->setSpeed(MoveSpeedMicros*0.9);
    else
      FAS->setSpeed(MoveSpeedMicros);
  }
}

Direct control of the acceleration independent of speed and position

Can the interface to the stepper driver be expanded so it become possible to directly control the acceleration of the motor independent of it's speed and position.

This will enable to use the steppers as acceleration devices (like DC-motors), which is used in many closed loop control systems.

Interrupt other PCNT

Hi ,

Use 3 PCNT for Quadrature Encoder with ISR for overflow. (run ISR Overflow OK)

Use your LIB with succes for 2 steppers and 1 frequency module.

Lost somes Interrupts on PCNT encoders overflow when FastAccelStepper -> engine.stepperConnectToPin

Howto fix it ?
(change priority or insert the ISR Quadrature Encoder in your LIB )

Thanks JF

Moving a set distance or angle.

Do you by chance have an example showing how to implament this for distance movement's?

I have a prety smart hybrid driver and a high torque stepper from Novotech. This library seems to work well with that combination although I am trying to split out the encoder signals so I can also get the positioning of the shaft rather then rely on limit switches.

in my case I am using micro 3200 steps on the driver. The project I have only needs to motor to turn one rotation forward and backward however I need to do this as fast as possible. Essentially thats 8.888 steps per degree.

I would like to be able to vary the velocity and speed of the movement over the 360 degree's of rotation but not quie sure how to implament this based on the examples.

Thanks in advance for any advice.
Andrew

Very high acceleration value e.g. 10.000.000 and high speed

Very high acceleration value e.g. 10.000.000 and high speed may be silently not executed, if the high speed in us is smaller than MIN_CMD_TICKS. This corresponds to 2500 steps/s for avr and 5000 steps/s.
=> Fix this, because problem occurs only, if the first command has only one step

Synchronise steppers

Howto synchronise multiple steppers ?
For start move 2 steppers
send a command wait Extern volatile int Synch ?

JF

Long step times are less accurate than short ones

If step time is longer than 65536 ticks, the actual step time is not tick accurate. The longer the step time the less accurate it gets. This is because the step time is approximated using a period time and a repetition count. In most cases this is not an issue since the error is small compared to the step time.
However in some cases tick accurate steps are needed (e.g. in my case, a barn door star tracker), otherwise the error accumulates and significant drift is introduced.

An alternative solution is to compose the step time using N fixed periods (each 65536-2*MIN_DELTA_TICKS long) plus any remaining ticks. I have implemented this solution for the AVR but have no idea how to do it for esp32 (so I cannot do a PR).

The downside to this is that the maximum step time is somewhat shorter (in the case of 16MHz AVR 1.034 instead of 1.044 seconds)

setPinsInverted() support for different modules

Hello, are you going to add setPinsInverted() support in the future? This might help the usage with different drivers or different connection configurations. This property exists in the AccelStepper library like so:
stepper.setPinsInverted(false, false, true);

Thanks in advance.

setCurrentPosition(0) does not reset moveTo(##), moveTo(##) still remembers old positon

We are at the point now where we're relating the pulse counter and stepper position both the physical world. We are able to reset both counters to 0, with the marker in the physical world, but using commands such as moveTo/move() we are running into limitations or we are not using it correctly where it seems to remember the original position even though we reset the pulse and position counters to 0. The construct for the stepper are not being reset even though the position counter is reset.

In the code below we are setting moveTo(-25599). As the motor is running to position -25599, we are setting the stepper position and pulse counter to 0. Although in the output the pulse counter and stepper position counters reset to 0 the moveTo/move(-25599) functions do not reset to zero and continues to remember the old position.
As a result the stepper moves -25599 steps instead of moving -25599 from the point the stepper position and counter has been set to 0.

void runStepperMotor()
{


  stepper->enableOutputs();
  stepper->moveTo(-25599);
  
  while(!((stepper->readPulseCounter() - 1) == (-25600))){
//  Serial.print(" -> PULSE COUNTER -1: ");
//  Serial.print(stepper->readPulseCounter() - 1);

  currentMillis = millis();
  if (stepper->pulseCounterAttached()) {
      Serial.print(" -> Pulse Counter: [");
      Serial.print(stepper->readPulseCounter());
      Serial.print(']');
      Serial.print(" -> Stepper Positon: [");
      Serial.print(stepper->getCurrentPosition());
      Serial.println(']');
      
//      Serial.print("TIME MILLIS: ");
//      Serial.print(currentMillis);
      }

  if(Serial.available()>0){
     if (Serial.read() == 'C') {
            Serial.print("Clear Counter");
            stepper->clearPulseCounter();
            stepper->setCurrentPosition(0);
        }
   }
    
    } //end of while loop
  
  Serial.print("Done Counting");
  stepper->clearPulseCounter();
  stepper->setCurrentPosition(0);

}

ESP32 forceStopAndNewPosition

often forceStopAndNewPosition(0) does not set position to 0. In that cases also something breaks and library stop to respond on moveTo function. Need more testing.

Can't use pins after ESP.restart()

I didn't wanted to open a new issue for this, but I gotta ask. Do you know why I can't drive a stepper manually after I use the ESP.restart() function? Do the pins stuck attached to something after restart? What I mean is digitalWrite functionality doesn't work on those pins. Maybe the library also gets broken, idk.

Problem with ESP32_DEVKIT V4 WROOM & StepperDemo

Hello,
I want to run a single stepper (200 steps per turn; 1A current spec) using an DRV8824 powered at 12V for the motor (DRV8824 trimpot adjusted).
I am using a win10 laptop and an Arduino environment.
When using an Arduino mega2560 hooked to a RAMPS card with A DRV8824, I get correct motion of the motor using a StepperDriver library (with acceleration/deceleration capability)

I want now to use a and an ESP32_DEVKIT V4 WROOM , and my goal is to use 6 steppers at 200 steps/turn, to rotate concurently each with an eventual different speed in the range 20RPM-800RPM

I have started to test only one motor; I am encountering problems; and would be happy to find a way to fix the problem:
I am using the "StepperDemo" from FastAccelStepper
I have used GPIO5 for stepping, GPIO27 for enable (enable_low_active), GPIO32 for direction; also I have hooked up a led in series with a 200 ohm resistance between pin GPIO5 and ground, so as to monitor step activity.

Here is what I get on the console:

ets Jun 8 2016 00:22:57

rst:0x1 (POWERON_RESET),boot:0x13 (SPI_FAST_FLASH_BOOT)
flash read err, 1000
ets_main.c 371
ets Jun 8 2016 00:22:57

rst:0x10 (RTCWDT_RTC_RESET),boot:0x13 (SPI_FAST_FLASH_BOOT)
configsip: 0, SPIWP:0xee
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
mode:DIO, clock div:1
load:0x3fff0018,len:4
load:0x3fff001c,len:1216
ho 0 tail 12 room 4
load:0x40078000,len:9720
ho 0 tail 12 room 4
load:0x40080400,len:6352
entry 0x400806b8
Demo Stepper
F_CPU=40000000
TICKS_PER_S=16000000
Enter commands separated by space, carriage return or newline:
M1/M2/.. ... to select stepper
A ... Set selected stepper's acceleration
V ... Set selected stepper's speed
U ... Update selected stepper's speed/acceleration while running
P ... Move selected stepper to position (can be negative)
R ... Move selected stepper by n steps (can be negative)
K ... Keep selected stepper running in current direction
@ ... Set selected stepper to position (can be negative)
E ... Set selected stepper's delay from enable to steps
D ... Set selected stepper's delay from steps to disable
N ... Turn selected stepper output on (disable auto enable)
F ... Turn selected stepper output off (disable auto enable)
O ... Put selected stepper into auto enable mode
S ... Stop selected stepper with deceleration
X ... Immediately stop motor and set zero position
I ... Toggle motor info, while any motor is running
W ... Blocking wait until selected motor is stopped (will deadlock if the motor will never stop)
+ ... Perform one step forward of the selected motor
- ... Perform one step backward of the selected motor
T ... Test selected motor with direct port access
Q ... Toggle print usage on motor stop
? ... Print this usage

M1: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
Select stepper 1
Set acceleration to 1000
Set speed (us) to 1000
Output driver on {>>> here the axis of the motor is not anymore free to rotate , which is OK}
Move to position 100
returncode=0
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=0 QueueEnd=1/0us Target=100 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
E (168457) task_wdt: Task watchdog got triggered. The following tasks did not reset the watchdog in time:
E (168457) task_wdt: - IDLE0 (CPU 0)
E (168457) task_wdt: Tasks currently running:
E (168457) task_wdt: CPU 0: StepperTask
E (168457) task_wdt: CPU 1: loopTask
E (168457) task_wdt: Aborting.
abort() was called at PC 0x400d5147 on core 0

Backtrace: 0x4008b820:0x3ffbe170 0x4008ba4d:0x3ffbe190 0x400d5147:0x3ffbe1b0 0x4008486d:0x3ffbe1d0 0x400d267d:0x3ffb86b0 0x400d18fe:0x3ffb86d0 0x400d1c1c:0x3ffb86f0 0x400d1db4:0x3ffb8720 0x400d1ebe:0x3ffb8760 0x400d1ed5:0x3ffb8780 0x400884d5:0x3ffb87a0

Rebooting...
ets Jun 8 2016 00:22:57


When the ESP32 boots , I can hear some noise from the motor1 ( vibration from the motor 1 but no net rotation, and the led on the GPIO5 is emitting light); this noise lasts for about 2 seconds ; then stops.
For the console output above,
I have typed the following commands:
M1
A1000
V1000
N
P100
The Move 100 is not associated with any activity on the GPIO5; The axis of the motor is not free to rotate until the errors encounter; then the program exits/reboots


I tried then a motion of larger amplitude:
ets Jun 8 2016 00:22:57

rst:0xc (SW_CPU_RESET),boot:0x13 (SPI_FAST_FLASH_BOOT)
configsip: 0, SPIWP:0xee
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
mode:DIO, clock div:1
load:0x3fff0018,len:4
load:0x3fff001c,len:1216
ho 0 tail 12 room 4
load:0x40078000,len:9720
ho 0 tail 12 room 4
load:0x40080400,len:6352
entry 0x400806b8
Demo Stepper
F_CPU=40000000
TICKS_PER_S=16000000
Enter commands separated by space, carriage return or newline:
M1/M2/.. ... to select stepper
A ... Set selected stepper's acceleration
V ... Set selected stepper's speed
U ... Update selected stepper's speed/acceleration while running
P ... Move selected stepper to position (can be negative)
R ... Move selected stepper by n steps (can be negative)
K ... Keep selected stepper running in current direction
@ ... Set selected stepper to position (can be negative)
E ... Set selected stepper's delay from enable to steps
D ... Set selected stepper's delay from steps to disable
N ... Turn selected stepper output on (disable auto enable)
F ... Turn selected stepper output off (disable auto enable)
O ... Put selected stepper into auto enable mode
S ... Stop selected stepper with deceleration
X ... Immediately stop motor and set zero position
I ... Toggle motor info, while any motor is running
W ... Blocking wait until selected motor is stopped (will deadlock if the motor will never stop)
+ ... Perform one step forward of the selected motor
- ... Perform one step backward of the selected motor
T ... Test selected motor with direct port access
Q ... Toggle print usage on motor stop
? ... Print this usage

M1: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
Select stepper 1
Set acceleration to 1000
Set speed (us) to 1000
Output driver on
Move to position 1000
returncode=0
M1: AUTO Curr=0 QueueEnd=0/0us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
(.......)
(.......)
(.......)
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
M1: AUTO Curr=1 QueueEnd=5/9984us Target=1000 RUN ACC M2: MANU Curr=0 QueueEnd=0/0us Target=0 STOP IDLE
ets Jun 8 2016 00:22:57


Similarly the led on GPIO5 is NOT turned on at all (no led activity)
I also tested the "T" command: it does apparently nothing that I could detect (axis of motor free to rotate or not, eventual noise of the motor, led on, etc...); Upon typing "T" and hitting return, I just get "nothing", and no feedback on the console either.

Reduce acceleration in unidirectional mode will lead to restart

Using M1 A1000 V100 P100 w300 A100 U.

The expectation is, that the motor will overshoot the position 100 and then stops, because it cannot reverse the direction. The overshoot is normal, because the acceleration has been reduced during ramp down.

Issue is, that the motor starts after stop to "reverse" in the same direction, because there is no direction pin connected. Second problem is, that the position even reduces to 100, which is totally wrong.

Even more weird is M1 A1000 V100 P100 w300 A100 U W P0, which according to the log returns to position 0.

(suggestion) Include setDelayToEnable and setDelayToDisable in usage example to fix TMC5160/etc. not moving

I am using a TTGO T-Display ESP32 and a TMC5160 SilentStepStick v1.5.

It took me a while before I found out what was making the StepperDemo example work while the usage example didn't (it would enable the driver but the motor did not move).

The answer was actually right under the usage example, but I missed it:

Some drivers need time to e.g. stabilize voltages until stepping should start. For this the start on delay has been added. See issue #5.

While trying to find the problem, I found that getCurrentPosition() would stay at 0 after a move() command when I didn't have the enable delays set. After adding

stepper->setDelayToEnable(50);
stepper->setDelayToDisable(1000);

to the usage example, everything worked as expected. I think it'd be good to add this to the usage example so it will work with more stepper drivers without needing modification.

It was confusing when getCurrentPosition() stayed at 0 because it seems like the ESP32 was actually aware that the driver didn't move the motor, but I thought that this shouldn't be possible since the driver doesn't send any information back to the ESP32 (at least not to FastAccelStepper, I should also mention that I'm using TMCStepper with software SPI).

Ramping stopped working at 4000 and 8000 counts/rev

Report from issue #44

Interestingly, at 4000 and 8000 counts/rev the ramping stopped working: hard reversals; hard stops; hard velocity changes. But also, at 8000, after some commands, speed stops responding to encoder turn or monitor commands.---The program seems to lose its way.

Real Time System Latency

Hi,
This is very nice and seems that very powerfull. I want to use this library on my realtime motion simulation project. I am currently processing commands from pc and generating pulses with arduino with interrupt timers, like you. But I dont have acceleration / decc routines, and I am very happy to found your library. Also nano/uno is not enought mcu power for 4 stepper. So ESP32 is also very vital for me.

My question is latency. I am asking only latency of library after run command. On docs, I saw 4ms for ATMEGA and 10ms for ESP, but I am not sure.

Thanks for help.

Steppers 4-6 issue

The steppers 4-6 do not work properly.

Try: M1 A10000 V300 f M4 A10000 V300 f

M4 runs slower than M1 and M4 makes more noise

An issue of M4 A10000 f or M4 V300 f makes stepper 4 slow down/speed up and M1 too makes noise. An issue of M4 f has no effect.

setAutoEnable() funcitonality

@gin66 Thank you very much for this library. This is the best stepper library I have used so far. I can drive stepper motors really fast using an ESP32 thanks to this. However, there is a slight issue on the auto enable function while using the setCurrentPosition().
For example, if I try this code:

homeAxis();

fastStepper.init();
axisStepper = fastStepper.stepperConnectToPin(AXIS_MOTOR_STEP_PIN);

if( axisStepper ) {
    axisStepper->setDirectionPin(AXIS_MOTOR_DIRECTION_PIN);
    axisStepper->setEnablePin(AXIS_MOTOR_ENABLE_PIN);
    axisStepper->setAutoEnable(true);
}
else {
    ESP.restart();
}

axisStepper->setCurrentPosition(0);

delay(1500);
axisStepper->setSpeed(30);
axisStepper->setAcceleration(5000);
axisStepper->moveTo(550400);

It homes the steppers using directly turning on and off the pins and then it sets the position to 0. After that, it moves to a given position which it can't reach correctly. It always misses it with some margin. I think this is due to starting driving the motors as soon as you enable them, because some drivers takes some time to adjust before actually pushing steps. If I change the code like this:

if( axisStepper ) {
    axisStepper->setDirectionPin(AXIS_MOTOR_DIRECTION_PIN);
    axisStepper->setEnablePin(AXIS_MOTOR_ENABLE_PIN);
    //axisStepper->setAutoEnable(true); <-Commented this line
}
else {
    ESP.restart();
}

axisStepper->enableOutputs(); //Manually enabling the outputs and waiting a little after that
delay(200);
axisStepper->setCurrentPosition(0);

delay(1500);
axisStepper->setSpeed(30);
axisStepper->setAcceleration(5000);
axisStepper->moveTo(550400);

it works without a problem. I think you need to give some time to the drivers before actually pushing steps to them. I don't know if you'd have the same issue with other drivers, but this is the case with my HPD-HBS57 closed loop stepper driver. It never misses any step due to its closed loop nature, however it misses steps with autoEnable turned on. I think you should wait a little before disabling the stepper motors between the commands and wait a little before starting them. This way they can have some time to adjust, and they wouldn't get turned on and off when there isn't any command in the queue immediately.

Thank you

Too many steps created

M1 A100000 V40 R1000 M2 A100000 V40 R1000

yields in simavr 1010 steps.

While M1 A100000 V40 R1000 yields as expected 1000 steps

With two steppers only speeds lower than ~430us work:
M1 A100000 V430 R1000 M2 A100000 V430 R1000

Usage example code not doing anything?

I didn't know where else to post this. I've tried using the example code on the Readme, and it doesn't do anything, but does seem to activate the stepper motor.

#include "FastAccelStepper.h"

#define dirPinStepper    2
#define enablePinStepper 4
#define stepPinStepper   3  // OC1A in case of AVR

FastAccelStepperEngine engine = FastAccelStepperEngine();
FastAccelStepper *stepper = NULL;

void setup() {
   engine.init();
   stepper = engine.stepperConnectToPin(stepPinStepper);
   if (stepper) {
      stepper->setDirectionPin(dirPinStepper);
      stepper->setEnablePin(enablePinStepper);
      stepper->setAutoEnable(true);

      stepper->setSpeed(1000);       // the parameter is us/step !!!
      stepper->setAcceleration(100);
   }
}

void loop() {
    stepper->moveTo(1000);
}

Does the FastAccelstepper library have some kind of stepper.run() function like accelstepper does?

I'm interested in using this library for a robotics project. It would be great to have a simple sweep code to begin with (stepper move clockwise.. stop. Stepper move anti-clockwise. Stop)

Problems with motors 4-6 on ESP32

Found your library and mostly its working great for me. Super glad to see a few today too!

I'm using an ESP32 (NodeMCU) and I cannot get the last 3 motors working. I've verified my wiring by switching positions (last 3 -> first 3, vice-versa) in the config array. Not real sure whats up, so I thought I'd reach out for help. Entirely possible I'm doing something dumb.

This is happening in my sketch (which only otherwise uses https://github.com/plapointe6/EspMQTTClient) and in the stepper demo sketch.

Config:

const struct stepper_config_s stepper_config[6] = {
    {
      step : 4,
      enable_low_active : 32,
      enable_high_active : PIN_UNDEFINED,
      direction : 5,
      direction_high_count_up : true,
      auto_enable : true,
      on_delay_us : 5000,
      off_delay_ms : 10
    },
    {
      step : 12,
      enable_low_active : 32,
      enable_high_active : PIN_UNDEFINED,
      direction : 13,
      direction_high_count_up : true,
      auto_enable : true,
      on_delay_us : 5000,
      off_delay_ms : 10
    },
    {
      step : 14,
      enable_low_active : 32,
      enable_high_active : PIN_UNDEFINED,
      direction : 15,
      direction_high_count_up : true,
      auto_enable : true,
      on_delay_us : 5000,
      off_delay_ms : 10
    },
    {
      step : 17,
      enable_low_active : 32,
      enable_high_active : PIN_UNDEFINED,
      direction : 18,
      direction_high_count_up : true,
      auto_enable : true,
      on_delay_us : 5000,
      off_delay_ms : 10
    },
    {
      step : 19,
      enable_low_active : 32,
      enable_high_active : PIN_UNDEFINED,
      direction : 21,
      direction_high_count_up : true,
      auto_enable : true,
      on_delay_us : 5000,
      off_delay_ms : 10
    },
    {
      step : 22,
      enable_low_active : 32,
      enable_high_active : PIN_UNDEFINED,
      direction : 23,
      direction_high_count_up : true,
      auto_enable : true,
      on_delay_us : 5000,
      off_delay_ms : 10
    },
    
};

Issue on moveTo() to exactly same target after a completion of stopMove()

If one issues any moveTo i.e. "moveTo(9999);" then, while on the way, issue a "stopMove()" and wait for a full stop, a re-issue of "moveTo(9999);" will NOT move the motor, any other value but previous one (9999) will work just fine. If the re-issue of the same "moveTo(9999);" occurs while the stepper is still moving (deceleration phase) everything runs fine. A current workaround this issue is to double call moveTo() with +1 value, i.e. "moveTo(value + 1);" followed by "moveTo(value);"

Motor stops running runBackard/runForward after executing forceStopAndNewPosition

Hi gin66,

Using executing runBackward() method a few times the motor stops running and does not respond to runBackward().

To explain our code:
We have a while loop and a timer for 30seconds.
Every time I enter a command to Start the motor, the motor will runBackward() for 30seconds and then stop (forceStopAndNewPosition) and wait for the next command again.
I will enter "Start" command again and the motor will run for 30seconds again and stop.

The problem is that after I "Start" the motor after the 2nd or 3rd time the motor will not run.
The timer is still running as expected and other parts of code are working as expected.
runBackward or runForward do not respond after 2nd/3rd time calling the method.

getCurrentPosition causes a block

It seems that using getCurrentPosition() causes the program to freeze/block. This is the code I am using:

#include "FastAccelStepper.h"

// As in StepperDemo for Motor 1 on AVR
#define dirPinStepper    9
#define enablePinStepper 10
#define stepPinStepper   8  // OC1A in case of AVR

// As in StepperDemo for Motor 1 on ESP32
//#define dirPinStepper 18
//#define enablePinStepper 26
//#define stepPinStepper 17

FastAccelStepperEngine engine = FastAccelStepperEngine();
FastAccelStepper *stepper = NULL;

void setup() {
 engine.init();
 stepper = engine.stepperConnectToPin(stepPinStepper);
 if (stepper) {
   stepper->setDirectionPin(dirPinStepper);
   stepper->setEnablePin(enablePinStepper);
   stepper->setAutoEnable(true);

   stepper->setSpeed(1000);  // the parameter is us/step !!!
   stepper->setAcceleration(10000);
   //stepper->move(7000);
   stepper->runForward();
 }
 Serial.begin(115200);
 Serial.print("    F_CPU=");
 Serial.println(F_CPU);
 Serial.print("    TICKS_PER_S=");
 Serial.println(TICKS_PER_S);  
}

void loop() 
{ 
   delayMicroseconds(100);
   if (stepper->isRunning()) 
   {
     Serial.print("@");
     Serial.print(stepper->getCurrentPosition());
   } 
}

Any idea why this might be happening?

setAcceleration cause wrong deceleration calculation (overshoot)

loop
{
stepper->setSpeed(variableSpeed);
//stepper->setAcceleration(9999); // uncomment this cause motor position will be over than target and motor have to go backward (same in both direction). In most bad cases it act like drunk car driver to chive target position in waves-like motion.
//stepper->setAcceleration(variableAcceleration); //same situation

long target = analogRead(A0)*5;
stepper->moveTo(target);
}

I test on ESP32. tested this on v0.18.11 , v0.18.02

ESP8266 ?

Hi,

is there a way to use this Prject on an ESP8266 ?

Best Regards

Andreas

Too much time in ISR

Time measurement with simavr has revealed critical timing under high speed with two or three parallel steppers.

Two steppers: 3720us spent in ISR, while repetition rate is 4096us

Three steppers: 3806us spent in ISR, while repetition rate is 4096us

At 25kSteps/s within 4096us, there will be 102 stepper interrupt/s created for one stepper and 306 stepper interrupts for three steppers. With max. 6us per Interrupt, during 4096us approx 1836us will be spent in the stepper interrupt.

Possible improvement:
1.) Update README to ensure not all steppers are running simultaneously at high speed
2.) Reduce time spent in stepper interrupt
3.) Reduce time spent in fill queue ISR
4.) Reduce max. step rate for 2560
5.) Reduce max. step rate dynamically from amount of steppers used.

Deceleration in applySpeedAcceleration() don't work.

I'm working with a potentiometer, setSpeed and applySpeedAcceleration. While the acceleration works perfect (by adding speed), there isn't an existing deceleration when decreasing the speed. It's jerky and jumpy getting slower.
With the methods "runForward" and "runBackward" it decelerates perfectly. Is it meant to be like that or isn't it implemented yet?

How many steppers can you control with acceleration?

I have been working on a motion control system using accelstepper for many months. The obvious drawback is that I can only control one stepper while implementing acceleration control. Can your library control two or more steppers with at least common acceleration values ? If so which board would you recommend. I am currently working with the RF-Nano

Why Timer4 only for Arduino Mega2560?

Hi! It is clearly stated in doc that for Arduino Mega2560 we can use only pins 6,7,8 (Timer4). But what is the reason? Can it be improved? In my project I have connected lcd display on mega2560, and these pins are used for display. I want to switch to Timer5 (pins 44,45,46), but it does not work :(

Stop and SetCurrentPosition methods

Hi Gin66,

Great library that you have here.

Do you have an update on when the SetCurrentPosition method will be done and do you have plans of having a Stop method in place to stop all current operations for the queue?

These operations are important when it comes to homing processes to find end of travel limits.
I am using the library with a nano (atmega328p)

Kind regards,
Jarryd

Error compiling example in Arduino IDE

Hi,
I get an error when trying to compile the simple avr example in Arduino IDE.
Arduino: 1.8.13 (Windows Store 1.8.42.0) (Windows 10), Board: "Arduino Nano, ATmega328P"
In file included from C:\Users\joerg\Documents\Arduino\sketch_sep07c\sketch_sep07c.ino:1:0:
C:\Users\joerg\Documents\Arduino\libraries\FastAccelStepper\src/FastAccelStepper.h:188:39: error: conversion from 'FastAccelStepper*' to non-scalar type 'FastAccelStepper' requested
#define stepperA() stepperConnectToPin(9)
C:\Users\joerg\Documents\Arduino\sketch_sep07c\sketch_sep07c.ino:8:40: note: in expansion of macro 'stepperA'
FastAccelStepper stepperA = fas_engine.stepperA();
^~~~~~~~
C:\Users\joerg\Documents\Arduino\sketch_sep07c\sketch_sep07c.ino: In function 'void setup()':
sketch_sep07c:13:12: error: base operand of '->' has non-pointer type 'FastAccelStepper'
stepperA->setDirectionPin(dirPinStepperA);
^~
sketch_sep07c:15:12: error: base operand of '->' has non-pointer type 'FastAccelStepper'
stepperA->setEnablePin(enablePinStepperA);
^~
sketch_sep07c:16:12: error: base operand of '->' has non-pointer type 'FastAccelStepper'
stepperA->setAutoEnable(true);
^~
sketch_sep07c:18:12: error: base operand of '->' has non-pointer type 'FastAccelStepper'
stepperA->setSpeed(1000); // the parameter is us/step !!!
^~
sketch_sep07c:19:12: error: base operand of '->' has non-pointer type 'FastAccelStepper'
stepperA->setAcceleration(100);
^~
sketch_sep07c:20:12: error: base operand of '->' has non-pointer type 'FastAccelStepper'
stepperA->move(1000);
^~

exit status 1
base operand of '->' has non-pointer type 'FastAccelStepper'

CODE

#include "FastAccelStepper.h"

#define dirPinStepperA 5
#define enablePinStepperA 6
//#define stepPinStepperA 9 // OC1A

FastAccelStepperEngine fas_engine = FastAccelStepperEngine();
FastAccelStepper stepperA = fas_engine.stepperA();
//FastAccelStepper stepperB = fas_engine.stepperB();

void setup() {
fas_engine.init();
stepperA->setDirectionPin(dirPinStepperA);

stepperA->setEnablePin(enablePinStepperA);
stepperA->setAutoEnable(true);

stepperA->setSpeed(1000); // the parameter is us/step !!!
stepperA->setAcceleration(100);
stepperA->move(1000);
}

void loop() {
}

esp32: Pulses lost with high speed

Version 0.18.2, commit b862e2e
Use this sequence in StepperDemo M1 p6 t 04 R

  1. Attach pulse counter M1 p7
  2. Test mode t
  3. run sequence 04 R

All ok.

Then x and M2 p7 t 04 R

Yields (sometimes) -2 for pulse counter, while position is 0

Comment to my HW: M1 and M2 share direction pin.

Using M3, which has not a shared direction, haven't seen this issue

Typo, bad paste & copy or forgotten ?

FastAccelStepper.c, line 484

_enablePinHighActive && _enablePinHighActive ?

  if ((_enablePinHighActive == PIN_UNDEFINED) &&
      (_enablePinHighActive == PIN_UNDEFINED)) {
    _externalEnableCall = NULL;
  }

Idea: add forwardStep() and backwardStep() functions for homing

As far as I can tell, the library does not include a stop function which would stop the stepper immediately without deceleration. However, this is needed for homing purposes in very precise devices. The homing function runs the stepper step by step until it hits an end stop or triggers a sensor. As soon as the end stop detected, the controller needs to stop the motor in order to get a very accurate position. It doesn't seem to be possible right now to do this using the library(Correct me if I'm wrong please). In fact I am doing it manually by toggling the step pin. What I'm suggesting is maybe we can add forwardStep() and backwardStep() functions to move the motor one step at a time to be able to check the sensor status at each step. What do you think about this? Thanks in advance.

Question on Demo/Test Program to Use to Verify FastAccelStepper Running on ESP32 to Operate A STAC6 Stepper Driver

Hi:

Just FYI background. We've been using the ESP32 MCU with the Easy Driver stepper driver till now. We have had some good results, but not perfect. The Easy Driver stepper driver modelues were just for the lab setup to develop our code, and now we're trying the FastAccelStepper out on a true industrial stepper driver (the STAC6-QE stepper driver) with a NEMA 34 1841 oz-in torque step motor.

A application is straight forward (I'll leave the encoder out of things on this question for simplicity, just interested in running the STAC6 stepper 6 correctly and smoothly for this industrial large NEMA 34 step motor on this question).

Just need FastAccelStepper to run on an inductrialized ESP32 MCU (Using Industrial Shields hardware as a ESP32 based PLC to control a stepper driver and step motor).

What is a good demo to test sketch to verify FastAccelStepper functionality and the set-up with a STAC6-QE stepper driver using FastAccelStepper running on an ESP32 using the Arduino IDE for the PLC code? Sorry, I don't see a "question" designation on here.

https://github.com/gin66/FastAccelStepper/tree/master/examples

Thanks for your help and time.

esp32: time adherence measurements yields anomally

Measurements by log from CuteCom line timestamps:
M1 N A100000 V100 R600000
...runs for 60s, OK
M1 N A100000 V1000 R60000
...runs for 60s,OK
M1 N A100000 V4000 R15000
...runs for 60s, OK
For speed >= 4096us additional pauses are added.
M1 N A100000 V4100 R14634
...runs for 30s ???
M1 N A100000 V5000 R12000
...runs for 30s ???
M1 N A100000 V10000 R6000
...runs for 25s ???
M1 N A100000 V12000 R5000
...runs for 20,5s ???
M1 N A100000 V15000 R4000
...runs for 32,8s ???
M1 N A100000 V20000 R3000
...runs for 37s ???
M1 N A100000 V100000 R600
...runs for 56s ???
M1 N A100000 V100000 R600
...runs for ~59,5s

All should yield 60s running time.

Stepper runs with V4100 much faster compared to V4000

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.