AccelStepper
AccelStepper.h
1// AccelStepper.h
2//
3/// \mainpage AccelStepper library for Arduino
4///
5/// This is the Arduino AccelStepper library.
6/// It provides an object-oriented interface for 2, 3 or 4 pin stepper motors and motor drivers.
7///
8/// The standard Arduino IDE includes the Stepper library
9/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is
10/// perfectly adequate for simple, single motor applications.
11///
12/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:
13/// \li Supports acceleration and deceleration
14/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper
15/// \li Most API functions never delay() or block (unless otherwise stated)
16/// \li Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers.
17/// \li Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library)
18/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)
19/// \li Very slow speeds are supported
20/// \li Extensive API
21/// \li Subclass support
22///
23/// The latest version of this documentation can be downloaded from
24/// http://www.airspayce.com/mikem/arduino/AccelStepper
25/// The version of the package that this documentation refers to can be downloaded
26/// from http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.66.zip
27///
28/// Example Arduino programs are included to show the main modes of use.
29///
30/// You can also find online help and discussion at http://groups.google.com/group/accelstepper
31/// Please use that group for all questions and discussions on this topic.
32/// Do not contact the author directly, unless it is to discuss commercial licensing.
33/// Before asking a question or reporting a bug, please read
34/// - http://en.wikipedia.org/wiki/Wikipedia:Reference_desk/How_to_ask_a_software_question
35/// - http://www.catb.org/esr/faqs/smart-questions.html
36/// - http://www.chiark.greenend.org.uk/~shgtatham/bugs.html
37///
38/// Beginners to C++ and stepper motors in general may find this helpful:
39/// - https://hackaday.io/project/183279-accelstepper-the-missing-manual
40/// - https://hackaday.io/project/183713-using-the-arduino-accelstepper-library
41///
42/// Tested on Arduino Diecimila and Mega with arduino-0018 & arduino-0021
43/// on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,
44/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.
45/// Tested on Teensy http://www.pjrc.com/teensy including Teensy 3.1 built using Arduino IDE 1.0.5 with
46/// teensyduino addon 1.18 and later.
47///
48/// \par Installation
49///
50/// Install in the usual way: unzip the distribution zip file to the libraries
51/// sub-folder of your sketchbook.
52///
53/// \par Theory
54///
55/// This code uses speed calculations as described in
56/// "Generate stepper-motor speed profiles in real time" by David Austin
57/// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf or
58/// http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time or
59/// http://web.archive.org/web/20140705143928/http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf
60/// with the exception that AccelStepper uses steps per second rather than radians per second
61/// (because we dont know the step angle of the motor)
62/// An initial step interval is calculated for the first step, based on the desired acceleration
63/// On subsequent steps, shorter step intervals are calculated based
64/// on the previous step until max speed is achieved.
65///
66/// \par Adafruit Motor Shield V2
67///
68/// The included examples AFMotor_* are for Adafruit Motor Shield V1 and do not work with Adafruit Motor Shield V2.
69/// See https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library for examples that work with Adafruit Motor Shield V2.
70///
71/// \par Donations
72///
73/// This library is offered under a free GPL license for those who want to use it that way.
74/// We try hard to keep it up to date, fix bugs
75/// and to provide free support. If this library has helped you save time or money, please consider donating at
76/// http://www.airspayce.com or here:
77///
78/// \htmlonly <form action="https://www.paypal.com/cgi-bin/webscr" method="post"><input type="hidden" name="cmd" value="_donations" /> <input type="hidden" name="business" value="mikem@airspayce.com" /> <input type="hidden" name="lc" value="AU" /> <input type="hidden" name="item_name" value="Airspayce" /> <input type="hidden" name="item_number" value="AccelStepper" /> <input type="hidden" name="currency_code" value="USD" /> <input type="hidden" name="bn" value="PP-DonationsBF:btn_donateCC_LG.gif:NonHosted" /> <input type="image" alt="PayPal — The safer, easier way to pay online." name="submit" src="https://www.paypalobjects.com/en_AU/i/btn/btn_donateCC_LG.gif" /> <img alt="" src="https://www.paypalobjects.com/en_AU/i/scr/pixel.gif" width="1" height="1" border="0" /></form> \endhtmlonly
79///
80/// \par Trademarks
81///
82/// AccelStepper is a trademark of AirSpayce Pty Ltd. The AccelStepper mark was first used on April 26 2010 for
83/// international trade, and is used only in relation to motor control hardware and software.
84/// It is not to be confused with any other similar marks covering other goods and services.
85///
86/// \par Copyright
87///
88/// This software is Copyright (C) 2009-2023 Mike McCauley. Use is subject to license
89/// conditions. The main licensing options available are GPL V3 or Commercial:
90///
91/// \par Open Source Licensing GPL V3
92/// This is the appropriate option if you want to share the source code of your
93/// application with everyone you distribute it to, and you also want to give them
94/// the right to share who uses it. If you wish to use this software under Open
95/// Source Licensing, you must contribute all your source code to the open source
96/// community in accordance with the GPL Version 23 when your application is
97/// distributed. See https://www.gnu.org/licenses/gpl-3.0.html
98///
99/// \par Commercial Licensing
100/// This is the appropriate option if you are creating proprietary applications
101/// and you are not prepared to distribute and share the source code of your
102/// application. To purchase a commercial license, contact info@airspayce.com
103///
104/// \par Revision History
105/// \version 1.0 Initial release
106///
107/// \version 1.1 Added speed() function to get the current speed.
108/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.
109/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1
110/// \version 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches.
111/// \version 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements
112/// to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width.
113/// Added checks for already running at max speed and skip further calcs if so.
114/// \version 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang.
115/// Reported by Sandy Noble.
116/// Removed redundant _lastRunTime member.
117/// \version 1.7 Fixed a bug where setCurrentPosition() did not always work as expected.
118/// Reported by Peter Linhart.
119/// \version 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon
120/// \version 1.9 setCurrentPosition() now also sets motor speed to 0.
121/// \version 1.10 Builds on Arduino 1.0
122/// \version 1.11 Improvments from Michael Ellison:
123/// Added optional enable line support for stepper drivers
124/// Added inversion for step/direction/enable lines for stepper drivers
125/// \version 1.12 Announce Google Group
126/// \version 1.13 Improvements to speed calculation. Cost of calculation is now less in the worst case,
127/// and more or less constant in all cases. This should result in slightly beter high speed performance, and
128/// reduce anomalous speed glitches when other steppers are accelerating.
129/// However, its hard to see how to replace the sqrt() required at the very first step from 0 speed.
130/// \version 1.14 Fixed a problem with compiling under arduino 0021 reported by EmbeddedMan
131/// \version 1.15 Fixed a problem with runSpeedToPosition which did not correctly handle
132/// running backwards to a smaller target position. Added examples
133/// \version 1.16 Fixed some cases in the code where abs() was used instead of fabs().
134/// \version 1.17 Added example ProportionalControl
135/// \version 1.18 Fixed a problem: If one calls the funcion runSpeed() when Speed is zero, it makes steps
136/// without counting. reported by Friedrich, Klappenbach.
137/// \version 1.19 Added MotorInterfaceType and symbolic names for the number of pins to use
138/// for the motor interface. Updated examples to suit.
139/// Replaced individual pin assignment variables _pin1, _pin2 etc with array _pin[4].
140/// _pins member changed to _interface.
141/// Added _pinInverted array to simplify pin inversion operations.
142/// Added new function setOutputPins() which sets the motor output pins.
143/// It can be overridden in order to provide, say, serial output instead of parallel output
144/// Some refactoring and code size reduction.
145/// \version 1.20 Improved documentation and examples to show need for correctly
146/// specifying AccelStepper::FULL4WIRE and friends.
147/// \version 1.21 Fixed a problem where desiredSpeed could compute the wrong step acceleration
148/// when _speed was small but non-zero. Reported by Brian Schmalz.
149/// Precompute sqrt_twoa to improve performance and max possible stepping speed
150/// \version 1.22 Added Bounce.pde example
151/// Fixed a problem where calling moveTo(), setMaxSpeed(), setAcceleration() more
152/// frequently than the step time, even
153/// with the same values, would interfere with speed calcs. Now a new speed is computed
154/// only if there was a change in the set value. Reported by Brian Schmalz.
155/// \version 1.23 Rewrite of the speed algorithms in line with
156/// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf
157/// Now expect smoother and more linear accelerations and decelerations. The desiredSpeed()
158/// function was removed.
159/// \version 1.24 Fixed a problem introduced in 1.23: with runToPosition, which did never returned
160/// \version 1.25 Now ignore attempts to set acceleration to 0.0
161/// \version 1.26 Fixed a problem where certina combinations of speed and accelration could cause
162/// oscillation about the target position.
163/// \version 1.27 Added stop() function to stop as fast as possible with current acceleration parameters.
164/// Also added new Quickstop example showing its use.
165/// \version 1.28 Fixed another problem where certain combinations of speed and acceleration could cause
166/// oscillation about the target position.
167/// Added support for 3 wire full and half steppers such as Hard Disk Drive spindle.
168/// Contributed by Yuri Ivatchkovitch.
169/// \version 1.29 Fixed a problem that could cause a DRIVER stepper to continually step
170/// with some sketches. Reported by Vadim.
171/// \version 1.30 Fixed a problem that could cause stepper to back up a few steps at the end of
172/// accelerated travel with certain speeds. Reported and patched by jolo.
173/// \version 1.31 Updated author and distribution location details to airspayce.com
174/// \version 1.32 Fixed a problem with enableOutputs() and setEnablePin on Arduino Due that
175/// prevented the enable pin changing stae correctly. Reported by Duane Bishop.
176/// \version 1.33 Fixed an error in example AFMotor_ConstantSpeed.pde did not setMaxSpeed();
177/// Fixed a problem that caused incorrect pin sequencing of FULL3WIRE and HALF3WIRE.
178/// Unfortunately this meant changing the signature for all step*() functions.
179/// Added example MotorShield, showing how to use AdaFruit Motor Shield to control
180/// a 3 phase motor such as a HDD spindle motor (and without using the AFMotor library.
181/// \version 1.34 Added setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
182/// to allow inversion of 2, 3 and 4 wire stepper pins. Requested by Oleg.
183/// \version 1.35 Removed default args from setPinsInverted(bool, bool, bool, bool, bool) to prevent ambiguity with
184/// setPinsInverted(bool, bool, bool). Reported by Mac Mac.
185/// \version 1.36 Changed enableOutputs() and disableOutputs() to be virtual so can be overridden.
186/// Added new optional argument 'enable' to constructor, which allows you toi disable the
187/// automatic enabling of outputs at construction time. Suggested by Guido.
188/// \version 1.37 Fixed a problem with step1 that could cause a rogue step in the
189/// wrong direction (or not,
190/// depending on the setup-time requirements of the connected hardware).
191/// Reported by Mark Tillotson.
192/// \version 1.38 run() function incorrectly always returned true. Updated function and doc so it returns true
193/// if the motor is still running to the target position.
194/// \version 1.39 Updated typos in keywords.txt, courtesey Jon Magill.
195/// \version 1.40 Updated documentation, including testing on Teensy 3.1
196/// \version 1.41 Fixed an error in the acceleration calculations, resulting in acceleration of haldf the intended value
197/// \version 1.42 Improved support for FULL3WIRE and HALF3WIRE output pins. These changes were in Yuri's original
198/// contribution but did not make it into production.<br>
199/// \version 1.43 Added DualMotorShield example. Shows how to use AccelStepper to control 2 x 2 phase steppers using the
200/// Itead Studio Arduino Dual Stepper Motor Driver Shield model IM120417015.<br>
201/// \version 1.44 examples/DualMotorShield/DualMotorShield.ino examples/DualMotorShield/DualMotorShield.pde
202/// was missing from the distribution.<br>
203/// \version 1.45 Fixed a problem where if setAcceleration was not called, there was no default
204/// acceleration. Reported by Michael Newman.<br>
205/// \version 1.45 Fixed inaccuracy in acceleration rate by using Equation 15, suggested by Sebastian Gracki.<br>
206/// Performance improvements in runSpeed suggested by Jaakko Fagerlund.<br>
207/// \version 1.46 Fixed error in documentation for runToPosition().
208/// Reinstated time calculations in runSpeed() since new version is reported
209/// not to work correctly under some circumstances. Reported by Oleg V Gavva.<br>
210/// \version 1.48 2015-08-25
211/// Added new class MultiStepper that can manage multiple AccelSteppers,
212/// and cause them all to move
213/// to selected positions at such a (constant) speed that they all arrive at their
214/// target position at the same time. Suitable for X-Y flatbeds etc.<br>
215/// Added new method maxSpeed() to AccelStepper to return the currently configured maxSpeed.<br>
216/// \version 1.49 2016-01-02
217/// Testing with VID28 series instrument stepper motors and EasyDriver.
218/// OK, although with light pointers
219/// and slow speeds like 180 full steps per second the motor movement can be erratic,
220/// probably due to some mechanical resonance. Best to accelerate through this speed.<br>
221/// Added isRunning().<br>
222/// \version 1.50 2016-02-25
223/// AccelStepper::disableOutputs now sets the enable pion to OUTPUT mode if the enable pin is defined.
224/// Patch from Piet De Jong.<br>
225/// Added notes about the fact that AFMotor_* examples do not work with Adafruit Motor Shield V2.<br>
226/// \version 1.51 2016-03-24
227/// Fixed a problem reported by gregor: when resetting the stepper motor position using setCurrentPosition() the
228/// stepper speed is reset by setting _stepInterval to 0, but _speed is not
229/// reset. this results in the stepper motor not starting again when calling
230/// setSpeed() with the same speed the stepper was set to before.
231/// \version 1.52 2016-08-09
232/// Added MultiStepper to keywords.txt.
233/// Improvements to efficiency of AccelStepper::runSpeed() as suggested by David Grayson.
234/// Improvements to speed accuracy as suggested by David Grayson.
235/// \version 1.53 2016-08-14
236/// Backed out Improvements to speed accuracy from 1.52 as it did not work correctly.
237/// \version 1.54 2017-01-24
238/// Fixed some warnings about unused arguments.
239/// \version 1.55 2017-01-25
240/// Fixed another warning in MultiStepper.cpp
241/// \version 1.56 2017-02-03
242/// Fixed minor documentation error with DIRECTION_CCW and DIRECTION_CW. Reported by David Mutterer.
243/// Added link to Binpress commercial license purchasing.
244/// \version 1.57 2017-03-28
245/// _direction moved to protected at the request of Rudy Ercek.
246/// setMaxSpeed() and setAcceleration() now correct negative values to be positive.
247/// \version 1.58 2018-04-13
248/// Add initialisation for _enableInverted in constructor.
249/// \version 1.59 2018-08-28
250/// Update commercial licensing, remove binpress.
251/// \version 1.60 2020-03-07
252/// Release under GPL V3
253/// \version 1.61 2020-04-20
254/// Added yield() call in runToPosition(), so that platforms like esp8266 dont hang/crash
255/// during long runs.
256/// \version 1.62 2022-05-22
257/// Added link to AccelStepper - The Missing Manual.<br>
258/// Fixed a problem when setting the maxSpeed to 1.0 due to incomplete initialisation.
259/// Reported by Olivier Pécheux. <br>
260/// \version 1.63 2022-06-30
261/// Added virtual destructor at the request of Jan.<br>
262/// \version 1.64 2022-10-31
263/// Patch courtesy acwest: Changes to make AccelStepper more subclassable. These changes are
264/// largely oriented to implementing new step-scheduling algorithms.<br>
265/// \Version 1.65 2025-04-25
266/// Updated Copyrights.<br>
267/// Added setAccelerationRoot() from Jonathan Newbrough
268/// for performance improvements if you have some sqare roots cached.<br>
269/// Converted all examples from .pde to .ino.<br>
270/// \Version 1.66 2026-01-21
271/// Fixed an issue with moving to negative positions with 3 wire Half Step, patched by Richard Hulme.<br>
272///
273/// \author Mike McCauley (mikem@airspayce.com) DO NOT CONTACT THE AUTHOR DIRECTLY: USE THE GOOGLE GROUP
274// Copyright (C) 2009-2025 Mike McCauley
275// $Id: AccelStepper.h,v 1.28 2020/04/20 00:15:03 mikem Exp mikem $
276
277#ifndef AccelStepper_h
278#define AccelStepper_h
279
280#include <stdlib.h>
281#if ARDUINO >= 100
282#include <Arduino.h>
283#else
284#include <WProgram.h>
285#include <wiring.h>
286#endif
287
288// These defs cause trouble on some versions of Arduino
289#undef round
290
291// Use the system yield() whenever possoible, since some platforms require it for housekeeping, especially
292// ESP8266
293#if (defined(ARDUINO) && ARDUINO >= 155) || defined(ESP8266)
294 #define YIELD yield();
295#else
296 #define YIELD
297#endif
298
299/////////////////////////////////////////////////////////////////////
300/// \class AccelStepper AccelStepper.h <AccelStepper.h>
301/// \brief Support for stepper motors with acceleration etc.
302///
303/// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional
304/// acceleration, deceleration, absolute positioning commands etc. Multiple
305/// simultaneous steppers are supported, all moving
306/// at different speeds and accelerations.
307///
308/// \par Operation
309/// This module operates by computing a step time in microseconds. The step
310/// time is recomputed after each step and after speed and acceleration
311/// parameters are changed by the caller. The time of each step is recorded in
312/// microseconds. The run() function steps the motor once if a new step is due.
313/// The run() function must be called frequently until the motor is in the
314/// desired position, after which time run() will do nothing.
315///
316/// \par Positioning
317/// Positions are specified by a signed long integer. At
318/// construction time, the current position of the motor is consider to be 0. Positive
319/// positions are clockwise from the initial position; negative positions are
320/// anticlockwise. The current position can be altered for instance after
321/// initialization positioning.
322///
323/// \par Caveats
324/// This is an open loop controller: If the motor stalls or is oversped,
325/// AccelStepper will not have a correct
326/// idea of where the motor really is (since there is no feedback of the motor's
327/// real position. We only know where we _think_ it is, relative to the
328/// initial starting point).
329///
330/// \par Performance
331/// The fastest motor speed that can be reliably supported is about 4000 steps per
332/// second at a clock frequency of 16 MHz on Arduino such as Uno etc.
333/// Faster processors can support faster stepping speeds.
334/// However, any speed less than that
335/// down to very slow speeds (much less than one per second) are also supported,
336/// provided the run() function is called frequently enough to step the motor
337/// whenever required for the speed set.
338/// Calling setAcceleration() is expensive,
339/// since it requires a square root to be calculated.
340///
341/// Gregor Christandl reports that with an Arduino Due and a simple test program,
342/// he measured 43163 steps per second using runSpeed(),
343/// and 16214 steps per second using run();
345{
346public:
347 /// \brief Symbolic names for number of pins.
348 /// Use this in the pins argument the AccelStepper constructor to
349 /// provide a symbolic name for the number of pins
350 /// to use.
351 typedef enum
352 {
353 FUNCTION = 0, ///< Use the functional interface, implementing your own driver functions (internal use only)
354 DRIVER = 1, ///< Stepper Driver, 2 driver pins required
355 FULL2WIRE = 2, ///< 2 wire stepper, 2 motor pins required
356 FULL3WIRE = 3, ///< 3 wire stepper, such as HDD spindle, 3 motor pins required
357 FULL4WIRE = 4, ///< 4 wire full stepper, 4 motor pins required
358 HALF3WIRE = 6, ///< 3 wire half stepper, such as HDD spindle, 3 motor pins required
359 HALF4WIRE = 8 ///< 4 wire half stepper, 4 motor pins required
361
362 /// Constructor. You can have multiple simultaneous steppers, all moving
363 /// at different speeds and accelerations, provided you call their run()
364 /// functions at frequent enough intervals. Current Position is set to 0, target
365 /// position is set to 0. MaxSpeed and Acceleration default to 1.0.
366 /// The motor pins will be initialised to OUTPUT mode during the
367 /// constructor by a call to enableOutputs().
368 /// \param[in] interface Number of pins to interface to. Integer values are
369 /// supported, but it is preferred to use the \ref MotorInterfaceType symbolic names.
370 /// AccelStepper::DRIVER (1) means a stepper driver (with Step and Direction pins).
371 /// If an enable line is also needed, call setEnablePin() after construction.
372 /// You may also invert the pins using setPinsInverted().
373 /// Caution: DRIVER implements a blocking delay of minPulseWidth microseconds (default 1us) for each step.
374 /// You can change this with setMinPulseWidth().
375 /// AccelStepper::FULL2WIRE (2) means a 2 wire stepper (2 pins required).
376 /// AccelStepper::FULL3WIRE (3) means a 3 wire stepper, such as HDD spindle (3 pins required).
377 /// AccelStepper::FULL4WIRE (4) means a 4 wire stepper (4 pins required).
378 /// AccelStepper::HALF3WIRE (6) means a 3 wire half stepper, such as HDD spindle (3 pins required)
379 /// AccelStepper::HALF4WIRE (8) means a 4 wire half stepper (4 pins required)
380 /// Defaults to AccelStepper::FULL4WIRE (4) pins.
381 /// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults
382 /// to pin 2. For a AccelStepper::DRIVER (interface==1),
383 /// this is the Step input to the driver. Low to high transition means to step)
384 /// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults
385 /// to pin 3. For a AccelStepper::DRIVER (interface==1),
386 /// this is the Direction input the driver. High means forward.
387 /// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults
388 /// to pin 4.
389 /// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults
390 /// to pin 5.
391 /// \param[in] enable If this is true (the default), enableOutputs() will be called to enable
392 /// the output pins at construction time.
393 AccelStepper(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5, bool enable = true);
394
395 /// Alternate Constructor which will call your own functions for forward and backward steps.
396 /// You can have multiple simultaneous steppers, all moving
397 /// at different speeds and accelerations, provided you call their run()
398 /// functions at frequent enough intervals. Current Position is set to 0, target
399 /// position is set to 0. MaxSpeed and Acceleration default to 1.0.
400 /// Any motor initialization should happen before hand, no pins are used or initialized.
401 /// \param[in] forward void-returning procedure that will make a forward step
402 /// \param[in] backward void-returning procedure that will make a backward step
403 AccelStepper(void (*forward)(), void (*backward)());
404
405 /// Set the target position. The run() function will try to move the motor (at most one step per call)
406 /// from the current position to the target position set by the most
407 /// recent call to this function. Caution: moveTo() also recalculates the speed for the next step.
408 /// If you are trying to use constant speed movements, you should call setSpeed() after calling moveTo().
409 /// \param[in] absolute The desired absolute position. Negative is
410 /// anticlockwise from the 0 position.
411 void moveTo(long absolute);
412
413 /// Set the target position relative to the current position.
414 /// \param[in] relative The desired position relative to the current position. Negative is
415 /// anticlockwise from the current position.
416 void move(long relative);
417
418 /// Poll the motor and step it if a step is due, implementing
419 /// accelerations and decelerations to achieve the target position. You must call this as
420 /// frequently as possible, but at least once per minimum step time interval,
421 /// preferably in your main loop. Note that each call to run() will make at most one step, and then only when a step is due,
422 /// based on the current speed and the time since the last step.
423 /// \return true if the motor is still running to the target position.
424 boolean run();
425
426 /// Poll the motor and step it if a step is due, implementing a constant
427 /// speed as set by the most recent call to setSpeed(). You must call this as
428 /// frequently as possible, but at least once per step interval,
429 /// \return true if the motor was stepped.
430 boolean runSpeed();
431
432 /// Sets the maximum permitted speed. The run() function will accelerate
433 /// up to the speed set by this function.
434 /// Caution: the maximum speed achievable depends on your processor and clock speed.
435 /// The default maxSpeed is 1.0 steps per second.
436 /// \param[in] speed The desired maximum speed in steps per second. Must
437 /// be > 0. Caution: Speeds that exceed the maximum speed supported by the processor may
438 /// Result in non-linear accelerations and decelerations.
439 void setMaxSpeed(float speed);
440
441 /// Returns the maximum speed configured for this stepper
442 /// that was previously set by setMaxSpeed();
443 /// \return The currently configured maximum speed
444 float maxSpeed();
445
446 /// Sets the acceleration/deceleration rate.
447 /// \param[in] acceleration The desired acceleration in steps per second
448 /// per second. Must be > 0.0. This is an expensive call since it requires a square
449 /// root to be calculated. Dont call more ofthen than needed.
450 void setAcceleration(float acceleration);
451
452 /// Sets the acceleration/deceleration rate, using the square root of the required acceleration.
453 /// This can be useful if you precompute square roots of required accelerations, which can yield performance
454 /// improvements if you frequently change ccelerations. Contributed by
455 /// \param[in] sqrtAcceleration The square root of the required acceleration in steps per second.
456 /// Must be > 0.0. Dont call more ofthen than needed.
457 void setAccelerationRoot(float sqrtAcceleration);
458
459 /// Returns the acceleration/deceleration rate configured for this stepper
460 /// that was previously set by setAcceleration();
461 /// \return The currently configured acceleration/deceleration
462 float acceleration();
463
464 /// Sets the desired constant speed for use with runSpeed().
465 /// \param[in] speed The desired constant speed in steps per
466 /// second. Positive is clockwise. Speeds of more than 1000 steps per
467 /// second are unreliable. Very slow speeds may be set (eg 0.00027777 for
468 /// once per hour, approximately. Speed accuracy depends on the Arduino
469 /// crystal. Jitter depends on how frequently you call the runSpeed() function.
470 /// The speed will be limited by the current value of setMaxSpeed()
471 void setSpeed(float speed);
472
473 /// The most recently set speed.
474 /// \return the most recent speed in steps per second
475 float speed();
476
477 /// The distance from the current position to the target position.
478 /// \return the distance from the current position to the target position
479 /// in steps. Positive is clockwise from the current position.
480 long distanceToGo();
481
482 /// The most recently set target position.
483 /// \return the target position
484 /// in steps. Positive is clockwise from the 0 position.
485 long targetPosition();
486
487 /// The current motor position.
488 /// \return the current motor position
489 /// in steps. Positive is clockwise from the 0 position.
490 long currentPosition();
491
492 /// Resets the current position of the motor, so that wherever the motor
493 /// happens to be right now is considered to be the new 0 position. Useful
494 /// for setting a zero position on a stepper after an initial hardware
495 /// positioning move.
496 /// Has the side effect of setting the current motor speed to 0.
497 /// \param[in] position The position in steps of wherever the motor
498 /// happens to be right now.
499 void setCurrentPosition(long position);
500
501 /// Moves the motor (with acceleration/deceleration)
502 /// to the target position and blocks until it is at
503 /// position. Dont use this in event loops, since it blocks.
504 void runToPosition();
505
506 /// Executes runSpeed() unless the targetPosition is reached.
507 /// This function needs to be called often just like runSpeed() or run().
508 /// Will step the motor if a step is required at the currently selected
509 /// speed unless the target position has been reached.
510 /// Does not implement accelerations.
511 /// \return true if it stepped
512 boolean runSpeedToPosition();
513
514 /// Moves the motor (with acceleration/deceleration)
515 /// to the new target position and blocks until it is at
516 /// position. Dont use this in event loops, since it blocks.
517 /// \param[in] position The new target position.
518 void runToNewPosition(long position);
519
520 /// Sets a new target position that causes the stepper
521 /// to stop as quickly as possible, using the current speed and acceleration parameters.
522 void stop();
523
524 /// Disable motor pin outputs by setting them all LOW
525 /// Depending on the design of your electronics this may turn off
526 /// the power to the motor coils, saving power.
527 /// This is useful to support Arduino low power modes: disable the outputs
528 /// during sleep and then reenable with enableOutputs() before stepping
529 /// again.
530 /// If the enable Pin is defined, sets it to OUTPUT mode and clears the pin to disabled.
531 virtual void disableOutputs();
532
533 /// Enable motor pin outputs by setting the motor pins to OUTPUT
534 /// mode. Called automatically by the constructor.
535 /// If the enable Pin is defined, sets it to OUTPUT mode and sets the pin to enabled.
536 virtual void enableOutputs();
537
538 /// Sets the minimum pulse width allowed by the stepper driver. The minimum practical pulse width is
539 /// approximately 20 microseconds. Times less than 20 microseconds
540 /// will usually result in 20 microseconds or so.
541 /// \param[in] minWidth The minimum pulse width in microseconds.
542 void setMinPulseWidth(unsigned int minWidth);
543
544 /// Sets the enable pin number for stepper drivers.
545 /// 0xFF indicates unused (default).
546 /// Otherwise, if a pin is set, the pin will be turned on when
547 /// enableOutputs() is called and switched off when disableOutputs()
548 /// is called.
549 /// \param[in] enablePin Arduino digital pin number for motor enable
550 /// \sa setPinsInverted
551 void setEnablePin(uint8_t enablePin = 0xff);
552
553 /// Sets the inversion for stepper driver pins
554 /// \param[in] directionInvert True for inverted direction pin, false for non-inverted
555 /// \param[in] stepInvert True for inverted step pin, false for non-inverted
556 /// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted
557 void setPinsInverted(bool directionInvert = false, bool stepInvert = false, bool enableInvert = false);
558
559 /// Sets the inversion for 2, 3 and 4 wire stepper pins
560 /// \param[in] pin1Invert True for inverted pin1, false for non-inverted
561 /// \param[in] pin2Invert True for inverted pin2, false for non-inverted
562 /// \param[in] pin3Invert True for inverted pin3, false for non-inverted
563 /// \param[in] pin4Invert True for inverted pin4, false for non-inverted
564 /// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted
565 void setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert);
566
567 /// Checks to see if the motor is currently running to a target
568 /// \return true if the speed is not zero or not at the target position
569 bool isRunning();
570
571 /// Virtual destructor to prevent warnings during delete
572 virtual ~AccelStepper() {};
573protected:
574
575 /// \brief Direction indicator
576 /// Symbolic names for the direction the motor is turning
577 typedef enum
578 {
579 DIRECTION_CCW = 0, ///< Counter-Clockwise
580 DIRECTION_CW = 1 ///< Clockwise
582
583 /// Forces the library to compute a new instantaneous speed and set that as
584 /// the current speed. It is called by
585 /// the library:
586 /// \li after each step
587 /// \li after change to maxSpeed through setMaxSpeed()
588 /// \li after change to acceleration through setAcceleration()
589 /// \li after change to target position (relative or absolute) through
590 /// move() or moveTo()
591 /// \return the new step interval
592 virtual unsigned long computeNewSpeed();
593
594 /// Low level function to set the motor output pins
595 /// bit 0 of the mask corresponds to _pin[0]
596 /// bit 1 of the mask corresponds to _pin[1]
597 /// You can override this to impment, for example serial chip output insted of using the
598 /// output pins directly
599 virtual void setOutputPins(uint8_t mask);
600
601 /// Called to execute a step. Only called when a new step is
602 /// required. Subclasses may override to implement new stepping
603 /// interfaces. The default calls step1(), step2(), step4() or step8() depending on the
604 /// number of pins defined for the stepper.
605 /// \param[in] step The current step phase number (0 to 7)
606 virtual void step(long step);
607
608 /// Called to execute a clockwise(+) step. Only called when a new step is
609 /// required. This increments the _currentPos and calls step()
610 /// \return the updated current position
611 long stepForward();
612
613 /// Called to execute a counter-clockwise(-) step. Only called when a new step is
614 /// required. This decrements the _currentPos and calls step()
615 /// \return the updated current position
616 long stepBackward();
617
618 /// Called to execute a step using stepper functions (pins = 0) Only called when a new step is
619 /// required. Calls _forward() or _backward() to perform the step
620 /// \param[in] step The current step phase number (0 to 7)
621 virtual void step0(long step);
622
623 /// Called to execute a step on a stepper driver (ie where pins == 1). Only called when a new step is
624 /// required. Subclasses may override to implement new stepping
625 /// interfaces. The default sets or clears the outputs of Step pin1 to step,
626 /// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond
627 /// which is the minimum STEP pulse width for the 3967 driver.
628 /// \param[in] step The current step phase number (0 to 7)
629 virtual void step1(long step);
630
631 /// Called to execute a step on a 2 pin motor. Only called when a new step is
632 /// required. Subclasses may override to implement new stepping
633 /// interfaces. The default sets or clears the outputs of pin1 and pin2
634 /// \param[in] step The current step phase number (0 to 7)
635 virtual void step2(long step);
636
637 /// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
638 /// required. Subclasses may override to implement new stepping
639 /// interfaces. The default sets or clears the outputs of pin1, pin2,
640 /// pin3
641 /// \param[in] step The current step phase number (0 to 7)
642 virtual void step3(long step);
643
644 /// Called to execute a step on a 4 pin motor. Only called when a new step is
645 /// required. Subclasses may override to implement new stepping
646 /// interfaces. The default sets or clears the outputs of pin1, pin2,
647 /// pin3, pin4.
648 /// \param[in] step The current step phase number (0 to 7)
649 virtual void step4(long step);
650
651 /// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
652 /// required. Subclasses may override to implement new stepping
653 /// interfaces. The default sets or clears the outputs of pin1, pin2,
654 /// pin3
655 /// \param[in] step The current step phase number (0 to 7)
656 virtual void step6(long step);
657
658 /// Called to execute a step on a 4 pin half-stepper motor. Only called when a new step is
659 /// required. Subclasses may override to implement new stepping
660 /// interfaces. The default sets or clears the outputs of pin1, pin2,
661 /// pin3, pin4.
662 /// \param[in] step The current step phase number (0 to 7)
663 virtual void step8(long step);
664
665 /// Current direction motor is spinning in
666 /// Protected because some peoples subclasses need it to be so
667 boolean _direction; // 1 == CW
668
669 /// The current interval between steps in microseconds.
670 /// 0 means the motor is currently stopped with _speed == 0
671 unsigned long _stepInterval;
672
673private:
674 /// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a
675 /// bipolar, and 4 pins is a unipolar.
676 uint8_t _interface; // 0, 1, 2, 4, 8, See MotorInterfaceType
677
678 /// Arduino pin number assignments for the 2 or 4 pins required to interface to the
679 /// stepper motor or driver
680 uint8_t _pin[4];
681
682 /// Whether the _pins is inverted or not
683 uint8_t _pinInverted[4];
684
685 /// The current absolution position in steps.
686 long _currentPos; // Steps
687
688 /// The target position in steps. The AccelStepper library will move the
689 /// motor from the _currentPos to the _targetPos, taking into account the
690 /// max speed, acceleration and deceleration
691 long _targetPos; // Steps
692
693 /// The current motos speed in steps per second
694 /// Positive is clockwise
695 float _speed; // Steps per second
696
697 /// The maximum permitted speed in steps per second. Must be > 0.
698 float _maxSpeed;
699
700 /// The acceleration to use to accelerate or decelerate the motor in steps
701 /// per second per second. Must be > 0
702 float _acceleration;
703 float _sqrt_twoa; // Precomputed sqrt(2*_acceleration)
704
705 /// The last step time in microseconds
706 unsigned long _lastStepTime;
707
708 /// The minimum allowed pulse width in microseconds
709 unsigned int _minPulseWidth;
710
711 /// Is the direction pin inverted?
712 ///bool _dirInverted; /// Moved to _pinInverted[1]
713
714 /// Is the step pin inverted?
715 ///bool _stepInverted; /// Moved to _pinInverted[0]
716
717 /// Is the enable pin inverted?
718 bool _enableInverted;
719
720 /// Enable pin for stepper driver, or 0xFF if unused.
721 uint8_t _enablePin;
722
723 /// The pointer to a forward-step procedure
724 void (*_forward)();
725
726 /// The pointer to a backward-step procedure
727 void (*_backward)();
728
729 /// The step counter for speed calculations
730 long _n;
731
732 /// Initial step size in microseconds
733 float _c0;
734
735 /// Last step size in microseconds
736 float _cn;
737
738 /// Min step size in microseconds based on maxSpeed
739 float _cmin; // at max speed
740
741};
742
743/// @example Random.ino
744/// Make a single stepper perform random changes in speed, position and acceleration
745
746/// @example Overshoot.ino
747/// Check overshoot handling
748/// which sets a new target position and then waits until the stepper has
749/// achieved it. This is used for testing the handling of overshoots
750
751/// @example MultipleSteppers.ino
752/// Shows how to multiple simultaneous steppers
753/// Runs one stepper forwards and backwards, accelerating and decelerating
754/// at the limits. Runs other steppers at the same time
755
756/// @example ConstantSpeed.ino
757/// Shows how to run AccelStepper in the simplest,
758/// fixed speed mode with no accelerations
759
760/// @example Blocking.ino
761/// Shows how to use the blocking call runToNewPosition
762/// Which sets a new target position and then waits until the stepper has
763/// achieved it.
764
765/// @example AFMotor_MultiStepper.ino
766/// Control both Stepper motors at the same time with different speeds
767/// and accelerations.
768
769/// @example AFMotor_ConstantSpeed.ino
770/// Shows how to run AccelStepper in the simplest,
771/// fixed speed mode with no accelerations
772
773/// @example ProportionalControl.ino
774/// Make a single stepper follow the analog value read from a pot or whatever
775/// The stepper will move at a constant speed to each newly set posiiton,
776/// depending on the value of the pot.
777
778/// @example Bounce.ino
779/// Make a single stepper bounce from one limit to another, observing
780/// accelrations at each end of travel
781
782/// @example Quickstop.ino
783/// Check stop handling.
784/// Calls stop() while the stepper is travelling at full speed, causing
785/// the stepper to stop as quickly as possible, within the constraints of the
786/// current acceleration.
787
788/// @example MotorShield.ino
789/// Shows how to use AccelStepper to control a 3-phase motor, such as a HDD spindle motor
790/// using the Adafruit Motor Shield http://www.ladyada.net/make/mshield/index.html.
791
792/// @example DualMotorShield.ino
793/// Shows how to use AccelStepper to control 2 x 2 phase steppers using the
794/// Itead Studio Arduino Dual Stepper Motor Driver Shield
795/// model IM120417015
796
797#endif
Support for stepper motors with acceleration etc.
Definition AccelStepper.h:345
void runToNewPosition(long position)
Definition AccelStepper.cpp:682
void setAccelerationRoot(float sqrtAcceleration)
Definition AccelStepper.cpp:304
void runToPosition()
Definition AccelStepper.cpp:664
boolean _direction
Definition AccelStepper.h:667
virtual void disableOutputs()
Definition AccelStepper.cpp:594
bool isRunning()
Definition AccelStepper.cpp:700
virtual void step6(long step)
Definition AccelStepper.cpp:519
float speed()
Definition AccelStepper.cpp:344
void setEnablePin(uint8_t enablePin=0xff)
Definition AccelStepper.cpp:635
long currentPosition()
Definition AccelStepper.cpp:82
boolean run()
Definition AccelStepper.cpp:185
float maxSpeed()
Definition AccelStepper.cpp:280
void stop()
Definition AccelStepper.cpp:688
virtual void step1(long step)
Definition AccelStepper.cpp:431
virtual void step2(long step)
Definition AccelStepper.cpp:448
void move(long relative)
Definition AccelStepper.cpp:33
MotorInterfaceType
Symbolic names for number of pins. Use this in the pins argument the AccelStepper constructor to prov...
Definition AccelStepper.h:352
@ HALF3WIRE
3 wire half stepper, such as HDD spindle, 3 motor pins required
Definition AccelStepper.h:358
@ FULL3WIRE
3 wire stepper, such as HDD spindle, 3 motor pins required
Definition AccelStepper.h:356
@ FULL2WIRE
2 wire stepper, 2 motor pins required
Definition AccelStepper.h:355
@ DRIVER
Stepper Driver, 2 driver pins required.
Definition AccelStepper.h:354
@ FULL4WIRE
4 wire full stepper, 4 motor pins required
Definition AccelStepper.h:357
@ HALF4WIRE
4 wire half stepper, 4 motor pins required
Definition AccelStepper.h:359
@ FUNCTION
Use the functional interface, implementing your own driver functions (internal use only)
Definition AccelStepper.h:353
unsigned long _stepInterval
Definition AccelStepper.h:671
Direction
Direction indicator Symbolic names for the direction the motor is turning.
Definition AccelStepper.h:578
@ DIRECTION_CCW
Counter-Clockwise.
Definition AccelStepper.h:579
@ DIRECTION_CW
Clockwise.
Definition AccelStepper.h:580
long distanceToGo()
Definition AccelStepper.cpp:72
virtual void step4(long step)
Definition AccelStepper.cpp:494
virtual ~AccelStepper()
Virtual destructor to prevent warnings during delete.
Definition AccelStepper.h:572
virtual void step(long step)
Definition AccelStepper.cpp:350
float acceleration()
Definition AccelStepper.cpp:324
boolean runSpeedToPosition()
Definition AccelStepper.cpp:670
long targetPosition()
Definition AccelStepper.cpp:77
void setCurrentPosition(long position)
Definition AccelStepper.cpp:89
virtual void enableOutputs()
Definition AccelStepper.cpp:606
virtual void step0(long step)
Definition AccelStepper.cpp:419
boolean runSpeed()
Definition AccelStepper.cpp:41
virtual void step8(long step)
Definition AccelStepper.cpp:555
virtual unsigned long computeNewSpeed()
Definition AccelStepper.cpp:98
void setMaxSpeed(float speed)
Definition AccelStepper.cpp:263
void setPinsInverted(bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)
Definition AccelStepper.cpp:647
void moveTo(long absolute)
Definition AccelStepper.cpp:23
virtual void step3(long step)
Definition AccelStepper.cpp:472
void setAcceleration(float acceleration)
Definition AccelStepper.cpp:285
void setSpeed(float speed)
Definition AccelStepper.cpp:329
virtual void setOutputPins(uint8_t mask)
Definition AccelStepper.cpp:406
long stepForward()
Definition AccelStepper.cpp:384
void setMinPulseWidth(unsigned int minWidth)
Definition AccelStepper.cpp:630
long stepBackward()
Definition AccelStepper.cpp:393