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