AccelStepper.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653
  1. // AccelStepper.cpp
  2. //
  3. // Copyright (C) 2009-2013 Mike McCauley
  4. // $Id: AccelStepper.cpp,v 1.23 2016/08/09 00:39:10 mikem Exp $
  5. #include "AccelStepper.h"
  6. #if 0
  7. // Some debugging assistance
  8. void dump(uint8_t* p, int l)
  9. {
  10. int i;
  11. for (i = 0; i < l; i++)
  12. {
  13. Serial.print(p[i], HEX);
  14. Serial.print(" ");
  15. }
  16. Serial.println("");
  17. }
  18. #endif
  19. void AccelStepper::moveTo(long absolute)
  20. {
  21. if (_targetPos != absolute)
  22. {
  23. _targetPos = absolute;
  24. computeNewSpeed();
  25. // compute new n?
  26. }
  27. }
  28. void AccelStepper::move(long relative)
  29. {
  30. moveTo(_currentPos + relative);
  31. }
  32. // Implements steps according to the current step interval
  33. // You must call this at least once per step
  34. // returns true if a step occurred
  35. boolean AccelStepper::runSpeed()
  36. {
  37. // Dont do anything unless we actually have a step interval
  38. if (!_stepInterval)
  39. return false;
  40. unsigned long time = micros();
  41. if (time - _lastStepTime >= _stepInterval)
  42. {
  43. if (_direction == DIRECTION_CW)
  44. {
  45. // Clockwise
  46. _currentPos += 1;
  47. }
  48. else
  49. {
  50. // Anticlockwise
  51. _currentPos -= 1;
  52. }
  53. step(_currentPos);
  54. _lastStepTime = time; // Caution: does not account for costs in step()
  55. return true;
  56. }
  57. else
  58. {
  59. return false;
  60. }
  61. }
  62. long AccelStepper::distanceToGo()
  63. {
  64. return _targetPos - _currentPos;
  65. }
  66. long AccelStepper::targetPosition()
  67. {
  68. return _targetPos;
  69. }
  70. long AccelStepper::currentPosition()
  71. {
  72. return _currentPos;
  73. }
  74. // Useful during initialisations or after initial positioning
  75. // Sets speed to 0
  76. void AccelStepper::setCurrentPosition(long position)
  77. {
  78. _targetPos = _currentPos = position;
  79. _n = 0;
  80. _stepInterval = 0;
  81. _speed = 0.0;
  82. }
  83. void AccelStepper::computeNewSpeed()
  84. {
  85. long distanceTo = distanceToGo(); // +ve is clockwise from curent location
  86. long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16
  87. if (distanceTo == 0 && stepsToStop <= 1)
  88. {
  89. // We are at the target and its time to stop
  90. _stepInterval = 0;
  91. _speed = 0.0;
  92. _n = 0;
  93. return;
  94. }
  95. if (distanceTo > 0)
  96. {
  97. // We are anticlockwise from the target
  98. // Need to go clockwise from here, maybe decelerate now
  99. if (_n > 0)
  100. {
  101. // Currently accelerating, need to decel now? Or maybe going the wrong way?
  102. if ((stepsToStop >= distanceTo) || _direction == DIRECTION_CCW)
  103. _n = -stepsToStop; // Start deceleration
  104. }
  105. else if (_n < 0)
  106. {
  107. // Currently decelerating, need to accel again?
  108. if ((stepsToStop < distanceTo) && _direction == DIRECTION_CW)
  109. _n = -_n; // Start accceleration
  110. }
  111. }
  112. else if (distanceTo < 0)
  113. {
  114. // We are clockwise from the target
  115. // Need to go anticlockwise from here, maybe decelerate
  116. if (_n > 0)
  117. {
  118. // Currently accelerating, need to decel now? Or maybe going the wrong way?
  119. if ((stepsToStop >= -distanceTo) || _direction == DIRECTION_CW)
  120. _n = -stepsToStop; // Start deceleration
  121. }
  122. else if (_n < 0)
  123. {
  124. // Currently decelerating, need to accel again?
  125. if ((stepsToStop < -distanceTo) && _direction == DIRECTION_CCW)
  126. _n = -_n; // Start accceleration
  127. }
  128. }
  129. // Need to accelerate or decelerate
  130. if (_n == 0)
  131. {
  132. // First step from stopped
  133. _cn = _c0;
  134. _direction = (distanceTo > 0) ? DIRECTION_CW : DIRECTION_CCW;
  135. }
  136. else
  137. {
  138. // Subsequent step. Works for accel (n is +_ve) and decel (n is -ve).
  139. _cn = _cn - ((2.0 * _cn) / ((4.0 * _n) + 1)); // Equation 13
  140. _cn = max(_cn, _cmin);
  141. }
  142. _n++;
  143. _stepInterval = _cn;
  144. _speed = 1000000.0 / _cn;
  145. if (_direction == DIRECTION_CCW)
  146. _speed = -_speed;
  147. #if 0
  148. Serial.println(_speed);
  149. Serial.println(_acceleration);
  150. Serial.println(_cn);
  151. Serial.println(_c0);
  152. Serial.println(_n);
  153. Serial.println(_stepInterval);
  154. Serial.println(distanceTo);
  155. Serial.println(stepsToStop);
  156. Serial.println("-----");
  157. #endif
  158. }
  159. // Run the motor to implement speed and acceleration in order to proceed to the target position
  160. // You must call this at least once per step, preferably in your main loop
  161. // If the motor is in the desired position, the cost is very small
  162. // returns true if the motor is still running to the target position.
  163. boolean AccelStepper::run()
  164. {
  165. if (runSpeed())
  166. computeNewSpeed();
  167. return _speed != 0.0 || distanceToGo() != 0;
  168. }
  169. AccelStepper::AccelStepper(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4, bool enable)
  170. {
  171. _interface = interface;
  172. _currentPos = 0;
  173. _targetPos = 0;
  174. _speed = 0.0;
  175. _maxSpeed = 1.0;
  176. _acceleration = 0.0;
  177. _sqrt_twoa = 1.0;
  178. _stepInterval = 0;
  179. _minPulseWidth = 1;
  180. _enablePin = 0xff;
  181. _lastStepTime = 0;
  182. _pin[0] = pin1;
  183. _pin[1] = pin2;
  184. _pin[2] = pin3;
  185. _pin[3] = pin4;
  186. _enableInverted = false;
  187. // NEW
  188. _n = 0;
  189. _c0 = 0.0;
  190. _cn = 0.0;
  191. _cmin = 1.0;
  192. _direction = DIRECTION_CCW;
  193. int i;
  194. for (i = 0; i < 4; i++)
  195. _pinInverted[i] = 0;
  196. if (enable)
  197. enableOutputs();
  198. // Some reasonable default
  199. setAcceleration(1);
  200. }
  201. AccelStepper::AccelStepper(void (*forward)(), void (*backward)())
  202. {
  203. _interface = 0;
  204. _currentPos = 0;
  205. _targetPos = 0;
  206. _speed = 0.0;
  207. _maxSpeed = 1.0;
  208. _acceleration = 0.0;
  209. _sqrt_twoa = 1.0;
  210. _stepInterval = 0;
  211. _minPulseWidth = 1;
  212. _enablePin = 0xff;
  213. _lastStepTime = 0;
  214. _pin[0] = 0;
  215. _pin[1] = 0;
  216. _pin[2] = 0;
  217. _pin[3] = 0;
  218. _forward = forward;
  219. _backward = backward;
  220. // NEW
  221. _n = 0;
  222. _c0 = 0.0;
  223. _cn = 0.0;
  224. _cmin = 1.0;
  225. _direction = DIRECTION_CCW;
  226. int i;
  227. for (i = 0; i < 4; i++)
  228. _pinInverted[i] = 0;
  229. // Some reasonable default
  230. setAcceleration(1);
  231. }
  232. void AccelStepper::setMaxSpeed(float speed)
  233. {
  234. if (speed < 0.0)
  235. speed = -speed;
  236. if (_maxSpeed != speed)
  237. {
  238. _maxSpeed = speed;
  239. _cmin = 1000000.0 / speed;
  240. // Recompute _n from current speed and adjust speed if accelerating or cruising
  241. if (_n > 0)
  242. {
  243. _n = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16
  244. computeNewSpeed();
  245. }
  246. }
  247. }
  248. float AccelStepper::maxSpeed()
  249. {
  250. return _maxSpeed;
  251. }
  252. void AccelStepper::setAcceleration(float acceleration)
  253. {
  254. if (acceleration == 0.0)
  255. return;
  256. if (acceleration < 0.0)
  257. acceleration = -acceleration;
  258. if (_acceleration != acceleration)
  259. {
  260. // Recompute _n per Equation 17
  261. _n = _n * (_acceleration / acceleration);
  262. // New c0 per Equation 7, with correction per Equation 15
  263. _c0 = 0.676 * sqrt(2.0 / acceleration) * 1000000.0; // Equation 15
  264. _acceleration = acceleration;
  265. computeNewSpeed();
  266. }
  267. }
  268. void AccelStepper::setSpeed(float speed)
  269. {
  270. if (speed == _speed)
  271. return;
  272. speed = constrain(speed, -_maxSpeed, _maxSpeed);
  273. if (speed == 0.0)
  274. _stepInterval = 0;
  275. else
  276. {
  277. _stepInterval = fabs(1000000.0 / speed);
  278. _direction = (speed > 0.0) ? DIRECTION_CW : DIRECTION_CCW;
  279. }
  280. _speed = speed;
  281. }
  282. float AccelStepper::speed()
  283. {
  284. return _speed;
  285. }
  286. // Subclasses can override
  287. void AccelStepper::step(long step)
  288. {
  289. switch (_interface)
  290. {
  291. case FUNCTION:
  292. step0(step);
  293. break;
  294. case DRIVER:
  295. step1(step);
  296. break;
  297. case FULL2WIRE:
  298. step2(step);
  299. break;
  300. case FULL3WIRE:
  301. step3(step);
  302. break;
  303. case FULL4WIRE:
  304. step4(step);
  305. break;
  306. case HALF3WIRE:
  307. step6(step);
  308. break;
  309. case HALF4WIRE:
  310. step8(step);
  311. break;
  312. }
  313. }
  314. // You might want to override this to implement eg serial output
  315. // bit 0 of the mask corresponds to _pin[0]
  316. // bit 1 of the mask corresponds to _pin[1]
  317. // ....
  318. void AccelStepper::setOutputPins(uint8_t mask)
  319. {
  320. uint8_t numpins = 2;
  321. if (_interface == FULL4WIRE || _interface == HALF4WIRE)
  322. numpins = 4;
  323. else if (_interface == FULL3WIRE || _interface == HALF3WIRE)
  324. numpins = 3;
  325. uint8_t i;
  326. for (i = 0; i < numpins; i++)
  327. digitalWrite(_pin[i], (mask & (1 << i)) ? (HIGH ^ _pinInverted[i]) : (LOW ^ _pinInverted[i]));
  328. }
  329. // 0 pin step function (ie for functional usage)
  330. void AccelStepper::step0(long step)
  331. {
  332. (void)(step); // Unused
  333. if (_speed > 0)
  334. _forward();
  335. else
  336. _backward();
  337. }
  338. // 1 pin step function (ie for stepper drivers)
  339. // This is passed the current step number (0 to 7)
  340. // Subclasses can override
  341. void AccelStepper::step1(long step)
  342. {
  343. (void)(step); // Unused
  344. // _pin[0] is step, _pin[1] is direction
  345. setOutputPins(_direction ? 0b10 : 0b00); // Set direction first else get rogue pulses
  346. setOutputPins(_direction ? 0b11 : 0b01); // step HIGH
  347. // Caution 200ns setup time
  348. // Delay the minimum allowed pulse width
  349. delayMicroseconds(_minPulseWidth);
  350. setOutputPins(_direction ? 0b10 : 0b00); // step LOW
  351. }
  352. // 2 pin step function
  353. // This is passed the current step number (0 to 7)
  354. // Subclasses can override
  355. void AccelStepper::step2(long step)
  356. {
  357. switch (step & 0x3)
  358. {
  359. case 0: /* 01 */
  360. setOutputPins(0b10);
  361. break;
  362. case 1: /* 11 */
  363. setOutputPins(0b11);
  364. break;
  365. case 2: /* 10 */
  366. setOutputPins(0b01);
  367. break;
  368. case 3: /* 00 */
  369. setOutputPins(0b00);
  370. break;
  371. }
  372. }
  373. // 3 pin step function
  374. // This is passed the current step number (0 to 7)
  375. // Subclasses can override
  376. void AccelStepper::step3(long step)
  377. {
  378. switch (step % 3)
  379. {
  380. case 0: // 100
  381. setOutputPins(0b100);
  382. break;
  383. case 1: // 001
  384. setOutputPins(0b001);
  385. break;
  386. case 2: //010
  387. setOutputPins(0b010);
  388. break;
  389. }
  390. }
  391. // 4 pin step function for half stepper
  392. // This is passed the current step number (0 to 7)
  393. // Subclasses can override
  394. void AccelStepper::step4(long step)
  395. {
  396. switch (step & 0x3)
  397. {
  398. case 0: // 1010
  399. setOutputPins(0b0101);
  400. break;
  401. case 1: // 0110
  402. setOutputPins(0b0110);
  403. break;
  404. case 2: //0101
  405. setOutputPins(0b1010);
  406. break;
  407. case 3: //1001
  408. setOutputPins(0b1001);
  409. break;
  410. }
  411. }
  412. // 3 pin half step function
  413. // This is passed the current step number (0 to 7)
  414. // Subclasses can override
  415. void AccelStepper::step6(long step)
  416. {
  417. switch (step % 6)
  418. {
  419. case 0: // 100
  420. setOutputPins(0b100);
  421. break;
  422. case 1: // 101
  423. setOutputPins(0b101);
  424. break;
  425. case 2: // 001
  426. setOutputPins(0b001);
  427. break;
  428. case 3: // 011
  429. setOutputPins(0b011);
  430. break;
  431. case 4: // 010
  432. setOutputPins(0b010);
  433. break;
  434. case 5: // 011
  435. setOutputPins(0b110);
  436. break;
  437. }
  438. }
  439. // 4 pin half step function
  440. // This is passed the current step number (0 to 7)
  441. // Subclasses can override
  442. void AccelStepper::step8(long step)
  443. {
  444. switch (step & 0x7)
  445. {
  446. case 0: // 1000
  447. setOutputPins(0b0001);
  448. break;
  449. case 1: // 1010
  450. setOutputPins(0b0101);
  451. break;
  452. case 2: // 0010
  453. setOutputPins(0b0100);
  454. break;
  455. case 3: // 0110
  456. setOutputPins(0b0110);
  457. break;
  458. case 4: // 0100
  459. setOutputPins(0b0010);
  460. break;
  461. case 5: //0101
  462. setOutputPins(0b1010);
  463. break;
  464. case 6: // 0001
  465. setOutputPins(0b1000);
  466. break;
  467. case 7: //1001
  468. setOutputPins(0b1001);
  469. break;
  470. }
  471. }
  472. // Prevents power consumption on the outputs
  473. void AccelStepper::disableOutputs()
  474. {
  475. if (! _interface) return;
  476. setOutputPins(0); // Handles inversion automatically
  477. if (_enablePin != 0xff)
  478. {
  479. pinMode(_enablePin, OUTPUT);
  480. digitalWrite(_enablePin, LOW ^ _enableInverted);
  481. }
  482. }
  483. void AccelStepper::enableOutputs()
  484. {
  485. if (! _interface)
  486. return;
  487. pinMode(_pin[0], OUTPUT);
  488. pinMode(_pin[1], OUTPUT);
  489. if (_interface == FULL4WIRE || _interface == HALF4WIRE)
  490. {
  491. pinMode(_pin[2], OUTPUT);
  492. pinMode(_pin[3], OUTPUT);
  493. }
  494. else if (_interface == FULL3WIRE || _interface == HALF3WIRE)
  495. {
  496. pinMode(_pin[2], OUTPUT);
  497. }
  498. if (_enablePin != 0xff)
  499. {
  500. pinMode(_enablePin, OUTPUT);
  501. digitalWrite(_enablePin, HIGH ^ _enableInverted);
  502. }
  503. }
  504. void AccelStepper::setMinPulseWidth(unsigned int minWidth)
  505. {
  506. _minPulseWidth = minWidth;
  507. }
  508. void AccelStepper::setEnablePin(uint8_t enablePin)
  509. {
  510. _enablePin = enablePin;
  511. // This happens after construction, so init pin now.
  512. if (_enablePin != 0xff)
  513. {
  514. pinMode(_enablePin, OUTPUT);
  515. digitalWrite(_enablePin, HIGH ^ _enableInverted);
  516. }
  517. }
  518. void AccelStepper::setPinsInverted(bool directionInvert, bool stepInvert, bool enableInvert)
  519. {
  520. _pinInverted[0] = stepInvert;
  521. _pinInverted[1] = directionInvert;
  522. _enableInverted = enableInvert;
  523. }
  524. void AccelStepper::setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
  525. {
  526. _pinInverted[0] = pin1Invert;
  527. _pinInverted[1] = pin2Invert;
  528. _pinInverted[2] = pin3Invert;
  529. _pinInverted[3] = pin4Invert;
  530. _enableInverted = enableInvert;
  531. }
  532. // Blocks until the target position is reached and stopped
  533. void AccelStepper::runToPosition()
  534. {
  535. while (run())
  536. ;
  537. }
  538. boolean AccelStepper::runSpeedToPosition()
  539. {
  540. if (_targetPos == _currentPos)
  541. return false;
  542. if (_targetPos >_currentPos)
  543. _direction = DIRECTION_CW;
  544. else
  545. _direction = DIRECTION_CCW;
  546. return runSpeed();
  547. }
  548. // Blocks until the new target position is reached
  549. void AccelStepper::runToNewPosition(long position)
  550. {
  551. moveTo(position);
  552. runToPosition();
  553. }
  554. void AccelStepper::stop()
  555. {
  556. if (_speed != 0.0)
  557. {
  558. long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)) + 1; // Equation 16 (+integer rounding)
  559. if (_speed > 0)
  560. move(stepsToStop);
  561. else
  562. move(-stepsToStop);
  563. }
  564. }
  565. bool AccelStepper::isRunning()
  566. {
  567. return !(_speed == 0.0 && _targetPos == _currentPos);
  568. }