AccelStepper.h 40 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735
  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.59.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-2018 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. To purchase a commercial license, contact info@airspayce.com
  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 acceleration 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. /// \version 1.57 2017-03-28
  241. /// _direction moved to protected at the request of Rudy Ercek.
  242. /// setMaxSpeed() and setAcceleration() now correct negative values to be positive.
  243. /// \version 1.58 2018-04-13
  244. /// Add initialisation for _enableInverted in constructor.
  245. /// \version 1.59 2018-08-28
  246. /// Update commercial licensing, remove binpress.
  247. ///
  248. /// \author Mike McCauley (mikem@airspayce.com) DO NOT CONTACT THE AUTHOR DIRECTLY: USE THE LISTS
  249. // Copyright (C) 2009-2013 Mike McCauley
  250. // $Id: AccelStepper.h,v 1.27 2016/08/14 10:26:54 mikem Exp mikem $
  251. #ifndef AccelStepper_h
  252. #define AccelStepper_h
  253. #include <stdlib.h>
  254. #if ARDUINO >= 100
  255. #include <Arduino.h>
  256. #else
  257. #include <WProgram.h>
  258. #include <wiring.h>
  259. #endif
  260. // These defs cause trouble on some versions of Arduino
  261. #undef round
  262. /////////////////////////////////////////////////////////////////////
  263. /// \class AccelStepper AccelStepper.h <AccelStepper.h>
  264. /// \brief Support for stepper motors with acceleration etc.
  265. ///
  266. /// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional
  267. /// acceleration, deceleration, absolute positioning commands etc. Multiple
  268. /// simultaneous steppers are supported, all moving
  269. /// at different speeds and accelerations.
  270. ///
  271. /// \par Operation
  272. /// This module operates by computing a step time in microseconds. The step
  273. /// time is recomputed after each step and after speed and acceleration
  274. /// parameters are changed by the caller. The time of each step is recorded in
  275. /// microseconds. The run() function steps the motor once if a new step is due.
  276. /// The run() function must be called frequently until the motor is in the
  277. /// desired position, after which time run() will do nothing.
  278. ///
  279. /// \par Positioning
  280. /// Positions are specified by a signed long integer. At
  281. /// construction time, the current position of the motor is consider to be 0. Positive
  282. /// positions are clockwise from the initial position; negative positions are
  283. /// anticlockwise. The current position can be altered for instance after
  284. /// initialization positioning.
  285. ///
  286. /// \par Caveats
  287. /// This is an open loop controller: If the motor stalls or is oversped,
  288. /// AccelStepper will not have a correct
  289. /// idea of where the motor really is (since there is no feedback of the motor's
  290. /// real position. We only know where we _think_ it is, relative to the
  291. /// initial starting point).
  292. ///
  293. /// \par Performance
  294. /// The fastest motor speed that can be reliably supported is about 4000 steps per
  295. /// second at a clock frequency of 16 MHz on Arduino such as Uno etc.
  296. /// Faster processors can support faster stepping speeds.
  297. /// However, any speed less than that
  298. /// down to very slow speeds (much less than one per second) are also supported,
  299. /// provided the run() function is called frequently enough to step the motor
  300. /// whenever required for the speed set.
  301. /// Calling setAcceleration() is expensive,
  302. /// since it requires a square root to be calculated.
  303. ///
  304. /// Gregor Christandl reports that with an Arduino Due and a simple test program,
  305. /// he measured 43163 steps per second using runSpeed(),
  306. /// and 16214 steps per second using run();
  307. class AccelStepper
  308. {
  309. public:
  310. /// \brief Symbolic names for number of pins.
  311. /// Use this in the pins argument the AccelStepper constructor to
  312. /// provide a symbolic name for the number of pins
  313. /// to use.
  314. typedef enum
  315. {
  316. FUNCTION = 0, ///< Use the functional interface, implementing your own driver functions (internal use only)
  317. DRIVER = 1, ///< Stepper Driver, 2 driver pins required
  318. FULL2WIRE = 2, ///< 2 wire stepper, 2 motor pins required
  319. FULL3WIRE = 3, ///< 3 wire stepper, such as HDD spindle, 3 motor pins required
  320. FULL4WIRE = 4, ///< 4 wire full stepper, 4 motor pins required
  321. HALF3WIRE = 6, ///< 3 wire half stepper, such as HDD spindle, 3 motor pins required
  322. HALF4WIRE = 8 ///< 4 wire half stepper, 4 motor pins required
  323. } MotorInterfaceType;
  324. /// Constructor. You can have multiple simultaneous steppers, all moving
  325. /// at different speeds and accelerations, provided you call their run()
  326. /// functions at frequent enough intervals. Current Position is set to 0, target
  327. /// position is set to 0. MaxSpeed and Acceleration default to 1.0.
  328. /// The motor pins will be initialised to OUTPUT mode during the
  329. /// constructor by a call to enableOutputs().
  330. /// \param[in] interface Number of pins to interface to. Integer values are
  331. /// supported, but it is preferred to use the \ref MotorInterfaceType symbolic names.
  332. /// AccelStepper::DRIVER (1) means a stepper driver (with Step and Direction pins).
  333. /// If an enable line is also needed, call setEnablePin() after construction.
  334. /// You may also invert the pins using setPinsInverted().
  335. /// AccelStepper::FULL2WIRE (2) means a 2 wire stepper (2 pins required).
  336. /// AccelStepper::FULL3WIRE (3) means a 3 wire stepper, such as HDD spindle (3 pins required).
  337. /// AccelStepper::FULL4WIRE (4) means a 4 wire stepper (4 pins required).
  338. /// AccelStepper::HALF3WIRE (6) means a 3 wire half stepper, such as HDD spindle (3 pins required)
  339. /// AccelStepper::HALF4WIRE (8) means a 4 wire half stepper (4 pins required)
  340. /// Defaults to AccelStepper::FULL4WIRE (4) pins.
  341. /// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults
  342. /// to pin 2. For a AccelStepper::DRIVER (interface==1),
  343. /// this is the Step input to the driver. Low to high transition means to step)
  344. /// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults
  345. /// to pin 3. For a AccelStepper::DRIVER (interface==1),
  346. /// this is the Direction input the driver. High means forward.
  347. /// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults
  348. /// to pin 4.
  349. /// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults
  350. /// to pin 5.
  351. /// \param[in] enable If this is true (the default), enableOutputs() will be called to enable
  352. /// the output pins at construction time.
  353. 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);
  354. /// Alternate Constructor which will call your own functions for forward and backward steps.
  355. /// You can have multiple simultaneous steppers, all moving
  356. /// at different speeds and accelerations, provided you call their run()
  357. /// functions at frequent enough intervals. Current Position is set to 0, target
  358. /// position is set to 0. MaxSpeed and Acceleration default to 1.0.
  359. /// Any motor initialization should happen before hand, no pins are used or initialized.
  360. /// \param[in] forward void-returning procedure that will make a forward step
  361. /// \param[in] backward void-returning procedure that will make a backward step
  362. AccelStepper(void (*forward)(), void (*backward)());
  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. /// Set the target position relative to the current position
  371. /// \param[in] relative The desired position relative to the current position. Negative is
  372. /// anticlockwise from the current position.
  373. void move(long relative);
  374. /// Poll the motor and step it if a step is due, implementing
  375. /// accelerations and decelerations to acheive the target position. You must call this as
  376. /// frequently as possible, but at least once per minimum step time interval,
  377. /// 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,
  378. /// based on the current speed and the time since the last step.
  379. /// \return true if the motor is still running to the target position.
  380. boolean run();
  381. /// Poll the motor and step it if a step is due, implementing a constant
  382. /// speed as set by the most recent call to setSpeed(). You must call this as
  383. /// frequently as possible, but at least once per step interval,
  384. /// \return true if the motor was stepped.
  385. boolean runSpeed();
  386. /// Sets the maximum permitted speed. The run() function will accelerate
  387. /// up to the speed set by this function.
  388. /// Caution: the maximum speed achievable depends on your processor and clock speed.
  389. /// The default maxSpeed is 1.0 steps per second.
  390. /// \param[in] speed The desired maximum speed in steps per second. Must
  391. /// be > 0. Caution: Speeds that exceed the maximum speed supported by the processor may
  392. /// Result in non-linear accelerations and decelerations.
  393. void setMaxSpeed(float speed);
  394. /// returns the maximum speed configured for this stepper
  395. /// that was previously set by setMaxSpeed();
  396. /// \return The currently configured maximum speed
  397. float maxSpeed();
  398. /// Sets the acceleration/deceleration rate.
  399. /// \param[in] acceleration The desired acceleration in steps per second
  400. /// per second. Must be > 0.0. This is an expensive call since it requires a square
  401. /// root to be calculated. Dont call more ofthen than needed
  402. void setAcceleration(float acceleration);
  403. /// Sets the desired constant speed for use with runSpeed().
  404. /// \param[in] speed The desired constant speed in steps per
  405. /// second. Positive is clockwise. Speeds of more than 1000 steps per
  406. /// second are unreliable. Very slow speeds may be set (eg 0.00027777 for
  407. /// once per hour, approximately. Speed accuracy depends on the Arduino
  408. /// crystal. Jitter depends on how frequently you call the runSpeed() function.
  409. /// The speed will be limited by the current value of setMaxSpeed()
  410. void setSpeed(float speed);
  411. /// The most recently set speed
  412. /// \return the most recent speed in steps per second
  413. float speed();
  414. /// The distance from the current position to the target position.
  415. /// \return the distance from the current position to the target position
  416. /// in steps. Positive is clockwise from the current position.
  417. long distanceToGo();
  418. /// The most recently set target position.
  419. /// \return the target position
  420. /// in steps. Positive is clockwise from the 0 position.
  421. long targetPosition();
  422. /// The currently motor position.
  423. /// \return the current motor position
  424. /// in steps. Positive is clockwise from the 0 position.
  425. long currentPosition();
  426. /// Resets the current position of the motor, so that wherever the motor
  427. /// happens to be right now is considered to be the new 0 position. Useful
  428. /// for setting a zero position on a stepper after an initial hardware
  429. /// positioning move.
  430. /// Has the side effect of setting the current motor speed to 0.
  431. /// \param[in] position The position in steps of wherever the motor
  432. /// happens to be right now.
  433. void setCurrentPosition(long position);
  434. /// Moves the motor (with acceleration/deceleration)
  435. /// to the target position and blocks until it is at
  436. /// position. Dont use this in event loops, since it blocks.
  437. void runToPosition();
  438. /// Runs at the currently selected speed until the target position is reached
  439. /// Does not implement accelerations.
  440. /// \return true if it stepped
  441. boolean runSpeedToPosition();
  442. /// Moves the motor (with acceleration/deceleration)
  443. /// to the new target position and blocks until it is at
  444. /// position. Dont use this in event loops, since it blocks.
  445. /// \param[in] position The new target position.
  446. void runToNewPosition(long position);
  447. /// Sets a new target position that causes the stepper
  448. /// to stop as quickly as possible, using the current speed and acceleration parameters.
  449. void stop();
  450. /// Disable motor pin outputs by setting them all LOW
  451. /// Depending on the design of your electronics this may turn off
  452. /// the power to the motor coils, saving power.
  453. /// This is useful to support Arduino low power modes: disable the outputs
  454. /// during sleep and then reenable with enableOutputs() before stepping
  455. /// again.
  456. /// If the enable Pin is defined, sets it to OUTPUT mode and clears the pin to disabled.
  457. virtual void disableOutputs();
  458. /// Enable motor pin outputs by setting the motor pins to OUTPUT
  459. /// mode. Called automatically by the constructor.
  460. /// If the enable Pin is defined, sets it to OUTPUT mode and sets the pin to enabled.
  461. virtual void enableOutputs();
  462. /// Sets the minimum pulse width allowed by the stepper driver. The minimum practical pulse width is
  463. /// approximately 20 microseconds. Times less than 20 microseconds
  464. /// will usually result in 20 microseconds or so.
  465. /// \param[in] minWidth The minimum pulse width in microseconds.
  466. void setMinPulseWidth(unsigned int minWidth);
  467. /// Sets the enable pin number for stepper drivers.
  468. /// 0xFF indicates unused (default).
  469. /// Otherwise, if a pin is set, the pin will be turned on when
  470. /// enableOutputs() is called and switched off when disableOutputs()
  471. /// is called.
  472. /// \param[in] enablePin Arduino digital pin number for motor enable
  473. /// \sa setPinsInverted
  474. void setEnablePin(uint8_t enablePin = 0xff);
  475. /// Sets the inversion for stepper driver pins
  476. /// \param[in] directionInvert True for inverted direction pin, false for non-inverted
  477. /// \param[in] stepInvert True for inverted step pin, false for non-inverted
  478. /// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted
  479. void setPinsInverted(bool directionInvert = false, bool stepInvert = false, bool enableInvert = false);
  480. /// Sets the inversion for 2, 3 and 4 wire stepper pins
  481. /// \param[in] pin1Invert True for inverted pin1, false for non-inverted
  482. /// \param[in] pin2Invert True for inverted pin2, false for non-inverted
  483. /// \param[in] pin3Invert True for inverted pin3, false for non-inverted
  484. /// \param[in] pin4Invert True for inverted pin4, false for non-inverted
  485. /// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted
  486. void setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert);
  487. /// Checks to see if the motor is currently running to a target
  488. /// \return true if the speed is not zero or not at the target position
  489. bool isRunning();
  490. protected:
  491. /// \brief Direction indicator
  492. /// Symbolic names for the direction the motor is turning
  493. typedef enum
  494. {
  495. DIRECTION_CCW = 0, ///< Counter-Clockwise
  496. DIRECTION_CW = 1 ///< Clockwise
  497. } Direction;
  498. /// Forces the library to compute a new instantaneous speed and set that as
  499. /// the current speed. It is called by
  500. /// the library:
  501. /// \li after each step
  502. /// \li after change to maxSpeed through setMaxSpeed()
  503. /// \li after change to acceleration through setAcceleration()
  504. /// \li after change to target position (relative or absolute) through
  505. /// move() or moveTo()
  506. void computeNewSpeed();
  507. /// Low level function to set the motor output pins
  508. /// bit 0 of the mask corresponds to _pin[0]
  509. /// bit 1 of the mask corresponds to _pin[1]
  510. /// You can override this to impment, for example serial chip output insted of using the
  511. /// output pins directly
  512. virtual void setOutputPins(uint8_t mask);
  513. /// Called to execute a step. Only called when a new step is
  514. /// required. Subclasses may override to implement new stepping
  515. /// interfaces. The default calls step1(), step2(), step4() or step8() depending on the
  516. /// number of pins defined for the stepper.
  517. /// \param[in] step The current step phase number (0 to 7)
  518. virtual void step(long step);
  519. /// Called to execute a step using stepper functions (pins = 0) Only called when a new step is
  520. /// required. Calls _forward() or _backward() to perform the step
  521. /// \param[in] step The current step phase number (0 to 7)
  522. virtual void step0(long step);
  523. /// Called to execute a step on a stepper driver (ie where pins == 1). Only called when a new step is
  524. /// required. Subclasses may override to implement new stepping
  525. /// interfaces. The default sets or clears the outputs of Step pin1 to step,
  526. /// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond
  527. /// which is the minimum STEP pulse width for the 3967 driver.
  528. /// \param[in] step The current step phase number (0 to 7)
  529. virtual void step1(long step);
  530. /// Called to execute a step on a 2 pin motor. Only called when a new step is
  531. /// required. Subclasses may override to implement new stepping
  532. /// interfaces. The default sets or clears the outputs of pin1 and pin2
  533. /// \param[in] step The current step phase number (0 to 7)
  534. virtual void step2(long step);
  535. /// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
  536. /// required. Subclasses may override to implement new stepping
  537. /// interfaces. The default sets or clears the outputs of pin1, pin2,
  538. /// pin3
  539. /// \param[in] step The current step phase number (0 to 7)
  540. virtual void step3(long step);
  541. /// Called to execute a step on a 4 pin motor. Only called when a new step is
  542. /// required. Subclasses may override to implement new stepping
  543. /// interfaces. The default sets or clears the outputs of pin1, pin2,
  544. /// pin3, pin4.
  545. /// \param[in] step The current step phase number (0 to 7)
  546. virtual void step4(long step);
  547. /// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
  548. /// required. Subclasses may override to implement new stepping
  549. /// interfaces. The default sets or clears the outputs of pin1, pin2,
  550. /// pin3
  551. /// \param[in] step The current step phase number (0 to 7)
  552. virtual void step6(long step);
  553. /// Called to execute a step on a 4 pin half-steper motor. Only called when a new step is
  554. /// required. Subclasses may override to implement new stepping
  555. /// interfaces. The default sets or clears the outputs of pin1, pin2,
  556. /// pin3, pin4.
  557. /// \param[in] step The current step phase number (0 to 7)
  558. virtual void step8(long step);
  559. /// Current direction motor is spinning in
  560. /// Protected because some peoples subclasses need it to be so
  561. boolean _direction; // 1 == CW
  562. private:
  563. /// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a
  564. /// bipolar, and 4 pins is a unipolar.
  565. uint8_t _interface; // 0, 1, 2, 4, 8, See MotorInterfaceType
  566. /// Arduino pin number assignments for the 2 or 4 pins required to interface to the
  567. /// stepper motor or driver
  568. uint8_t _pin[4];
  569. /// Whether the _pins is inverted or not
  570. uint8_t _pinInverted[4];
  571. /// The current absolution position in steps.
  572. long _currentPos; // Steps
  573. /// The target position in steps. The AccelStepper library will move the
  574. /// motor from the _currentPos to the _targetPos, taking into account the
  575. /// max speed, acceleration and deceleration
  576. long _targetPos; // Steps
  577. /// The current motos speed in steps per second
  578. /// Positive is clockwise
  579. float _speed; // Steps per second
  580. /// The maximum permitted speed in steps per second. Must be > 0.
  581. float _maxSpeed;
  582. /// The acceleration to use to accelerate or decelerate the motor in steps
  583. /// per second per second. Must be > 0
  584. float _acceleration;
  585. float _sqrt_twoa; // Precomputed sqrt(2*_acceleration)
  586. /// The current interval between steps in microseconds.
  587. /// 0 means the motor is currently stopped with _speed == 0
  588. unsigned long _stepInterval;
  589. /// The last step time in microseconds
  590. unsigned long _lastStepTime;
  591. /// The minimum allowed pulse width in microseconds
  592. unsigned int _minPulseWidth;
  593. /// Is the direction pin inverted?
  594. ///bool _dirInverted; /// Moved to _pinInverted[1]
  595. /// Is the step pin inverted?
  596. ///bool _stepInverted; /// Moved to _pinInverted[0]
  597. /// Is the enable pin inverted?
  598. bool _enableInverted;
  599. /// Enable pin for stepper driver, or 0xFF if unused.
  600. uint8_t _enablePin;
  601. /// The pointer to a forward-step procedure
  602. void (*_forward)();
  603. /// The pointer to a backward-step procedure
  604. void (*_backward)();
  605. /// The step counter for speed calculations
  606. long _n;
  607. /// Initial step size in microseconds
  608. float _c0;
  609. /// Last step size in microseconds
  610. float _cn;
  611. /// Min step size in microseconds based on maxSpeed
  612. float _cmin; // at max speed
  613. };
  614. /// @example Random.pde
  615. /// Make a single stepper perform random changes in speed, position and acceleration
  616. /// @example Overshoot.pde
  617. /// Check overshoot handling
  618. /// which sets a new target position and then waits until the stepper has
  619. /// achieved it. This is used for testing the handling of overshoots
  620. /// @example MultipleSteppers.pde
  621. /// Shows how to multiple simultaneous steppers
  622. /// Runs one stepper forwards and backwards, accelerating and decelerating
  623. /// at the limits. Runs other steppers at the same time
  624. /// @example ConstantSpeed.pde
  625. /// Shows how to run AccelStepper in the simplest,
  626. /// fixed speed mode with no accelerations
  627. /// @example Blocking.pde
  628. /// Shows how to use the blocking call runToNewPosition
  629. /// Which sets a new target position and then waits until the stepper has
  630. /// achieved it.
  631. /// @example AFMotor_MultiStepper.pde
  632. /// Control both Stepper motors at the same time with different speeds
  633. /// and accelerations.
  634. /// @example AFMotor_ConstantSpeed.pde
  635. /// Shows how to run AccelStepper in the simplest,
  636. /// fixed speed mode with no accelerations
  637. /// @example ProportionalControl.pde
  638. /// Make a single stepper follow the analog value read from a pot or whatever
  639. /// The stepper will move at a constant speed to each newly set posiiton,
  640. /// depending on the value of the pot.
  641. /// @example Bounce.pde
  642. /// Make a single stepper bounce from one limit to another, observing
  643. /// accelrations at each end of travel
  644. /// @example Quickstop.pde
  645. /// Check stop handling.
  646. /// Calls stop() while the stepper is travelling at full speed, causing
  647. /// the stepper to stop as quickly as possible, within the constraints of the
  648. /// current acceleration.
  649. /// @example MotorShield.pde
  650. /// Shows how to use AccelStepper to control a 3-phase motor, such as a HDD spindle motor
  651. /// using the Adafruit Motor Shield http://www.ladyada.net/make/mshield/index.html.
  652. /// @example DualMotorShield.pde
  653. /// Shows how to use AccelStepper to control 2 x 2 phase steppers using the
  654. /// Itead Studio Arduino Dual Stepper Motor Driver Shield
  655. /// model IM120417015
  656. #endif