Atm_AccelStepper.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727
  1. #include "Atm_AccelStepper.h"
  2. /* Add optional parameters for the state machine to begin()
  3. * Add extra initialization code
  4. */
  5. Atm_AccelStepper& Atm_AccelStepper::begin(int step_pin, int dir_pin) {
  6. // clang-format off
  7. const static state_t state_table[] PROGMEM = {
  8. /* ON_ENTER ON_LOOP ON_EXIT EVT_DISABLE EVT_ENABLE EVT_ENABLED_TIMEOUT EVT_MOVE EVT_STOP EVT_EMERGENCY_STOP EVT_ON_LIMIT_LOW EVT_ON_LIMIT_HIGH EVT_ON_TARGET EVT_HOMING_LOW EVT_HOMING_HIGH ELSE */
  9. /* DISABLE */ ENT_DISABLED, -1, -1, -1, ENABLED, -1, RUNNING, -1, -1, DISABLE, DISABLE, -1, HOMING_LOW, HOMING_HIGH, -1,
  10. /* ENABLED */ ENT_ENABLED, -1, -1, DISABLE, -1, DISABLE, RUNNING, STOP, STOP, ENABLED, ENABLED, -1, HOMING_LOW, HOMING_HIGH, -1,
  11. /* RUNNING */ ENT_RUNNING, LP_RUNNING, -1, DISABLE, -1, -1, RUNNING, STOP, STOP, RUNNING, RUNNING, ENABLED, -1, -1, -1,
  12. /* STOP */ ENT_STOP, LP_STOP, -1, DISABLE, -1, -1, RUNNING, STOP, STOP, STOP, STOP, ENABLED, -1, -1, -1,
  13. /* HOMING_LOW */ ENT_HOMING_LOW, LP_HOMING_LOW, EXT_HOMING_LOW, DISABLE, -1, -1, -1, STOP, STOP, HOMING_LOW, HOMING_LOW, -1, -1, -1, -1,
  14. /* HOMING_HIGH */ ENT_HOMING_HIGH, LP_HOMING_HIGH, EXT_HOMING_HIGH, DISABLE, -1, -1, -1, STOP, STOP, HOMING_HIGH, HOMING_HIGH, -1, -1, -1, -1,
  15. /* LIMIT_LOW */ ENT_LIMIT_LOW, LP_LIMIT_LOW, -1, -1, -1, -1, RUNNING, STOP, STOP, -1, -1, -1, -1, -1, -1,
  16. /* LIMIT_HIGH */ ENT_LIMIT_HIGH, LP_LIMIT_HIGH, -1, -1, -1, -1, RUNNING, STOP, STOP, -1, -1, -1, -1, -1, -1
  17. };
  18. // clang-format on
  19. Machine::begin( state_table, ELSE );
  20. stepper = new AccelStepper(1, step_pin, dir_pin);
  21. stepper->setMaxSpeed(max_speed);
  22. stepper->setAcceleration(acceleration);
  23. idle_timer.set(ATM_TIMER_OFF);
  24. position_timer.set(POSITION_SEND_TIMER);
  25. return *this;
  26. }
  27. /* Add C++ code for each internally handled event (input)
  28. * The code must return 1 to trigger the event
  29. */
  30. int Atm_AccelStepper::event( int id ) {
  31. bool tempState ;
  32. switch ( id ) {
  33. case EVT_DISABLE:
  34. return 0;
  35. case EVT_ENABLE:
  36. return 0;
  37. case EVT_ENABLED_TIMEOUT:
  38. return 0;
  39. case EVT_MOVE:
  40. return 0;
  41. case EVT_STOP:
  42. return 0;
  43. case EVT_EMERGENCY_STOP:
  44. return 0;
  45. case EVT_ON_LIMIT_LOW:
  46. switch(_limitLow_Mode) {
  47. case 0:
  48. break;
  49. case 1: //digital INPUT
  50. // Serial.println("digital");
  51. limitLow_State_raw = digitalRead(_limitLow_Pin);
  52. limitLow_State_raw = _limitLow_Reversed ? !limitLow_State_raw : limitLow_State_raw;
  53. break;
  54. case 2:
  55. int analogTemp = analogRead(_limitLow_Pin);
  56. limitLow_State_raw = (_limitLow_Thresholds[0] < analogTemp) && (analogTemp < _limitLow_Thresholds[1]);
  57. limitLow_State_raw = _limitLow_Reversed ? !limitLow_State_raw : limitLow_State_raw;
  58. // if(limitLow_State){
  59. // delay(3);
  60. // analogTemp = analogRead(_limitLow_Pin);
  61. // limitLow_State = (_limitLow_Thresholds[0] < analogTemp) && (analogTemp < _limitLow_Thresholds[1]);
  62. // limitLow_State = _limitLow_Reversed ? !limitLow_State : limitLow_State;
  63. // }
  64. break;
  65. }
  66. limitLow_State = limitLow_avg(limitLow_State_raw);
  67. changed = limitLow_State != limitLow_State_prev ? 1 : 0 ;
  68. limitLow_State_prev = limitLow_State ;
  69. //Serial.println(limitLow_State);
  70. if (changed){push( connectors, ON_ONLIMITLOW, 0, limitLow_State, 0 );}
  71. return changed ;
  72. case EVT_ON_LIMIT_HIGH:
  73. switch(_limitHigh_Mode) {
  74. case 0:
  75. break;
  76. case 1: //digital INPUT
  77. limitHigh_State_raw = digitalRead(_limitHigh_Pin);
  78. limitHigh_State_raw = _limitHigh_Reversed ? !limitHigh_State_raw : limitHigh_State_raw;
  79. break;
  80. case 2:
  81. //Serial.println("analog");
  82. int analogTemp = analogRead(_limitHigh_Pin);
  83. limitHigh_State_raw = (_limitHigh_Thresholds[0] < analogTemp) && (analogTemp < _limitHigh_Thresholds[1]);
  84. limitHigh_State_raw = _limitHigh_Reversed ? !limitHigh_State_raw : limitHigh_State_raw;
  85. // if(limitHigh_State){
  86. // delay(3);
  87. // analogTemp = analogRead(_limitHigh_Pin);
  88. // limitHigh_State = (_limitHigh_Thresholds[0] < analogTemp) && (analogTemp < _limitHigh_Thresholds[1]);
  89. // limitHigh_State = _limitHigh_Reversed ? !limitHigh_State : limitHigh_State;
  90. // }
  91. break;
  92. }
  93. limitHigh_State = limitHigh_avg(limitHigh_State_raw);
  94. changed = limitHigh_State != limitHigh_State_prev ? 1 : 0;
  95. limitHigh_State_prev = limitHigh_State;
  96. if (changed){push( connectors, ON_ONLIMITHIGH, 0, limitHigh_State, 0 );}
  97. return changed;
  98. case EVT_ON_TARGET:
  99. return runMode ? 0 : _currentStep == _targetStep;
  100. case EVT_HOMING_LOW:
  101. return 0;
  102. case EVT_HOMING_HIGH:
  103. return 0;
  104. }
  105. return 0;
  106. }
  107. /* Add C++ code for each action
  108. * This generates the 'output' for the state machine
  109. *
  110. * Available connectors:
  111. * push( connectors, ON_CHANGEPOSITION, 0, <v>, <up> );
  112. * push( connectors, ON_CHANGESTATE, 0, <v>, <up> );
  113. * push( connectors, ON_ONLIMITHIGH, 0, <v>, <up> );
  114. * push( connectors, ON_ONLIMITLOW, 0, <v>, <up> );
  115. * push( connectors, ON_ONTARGET, 0, <v>, <up> );
  116. * push( connectors, ON_STOP, 0, <v>, <up> );
  117. */
  118. void Atm_AccelStepper::action( int id ) {
  119. switch ( id ) {
  120. case ENT_DISABLED:
  121. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  122. enabled = _enableReversed ? HIGH : LOW;
  123. digitalWrite(_enablePin, enabled);
  124. return;
  125. case ENT_ENABLED:
  126. _isHoming = 0 ;
  127. stepper_update();
  128. if(last_trigger == EVT_ON_TARGET){push( connectors, ON_ONTARGET, 0, _currentStep, 0 );};
  129. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  130. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  131. enabled = _enableReversed ? LOW : HIGH ;
  132. //reset limit state so that they trigger again if we're stopped on it
  133. limitLow_State = 0;
  134. limitHigh_State = 0;
  135. digitalWrite(_enablePin, enabled);
  136. return;
  137. case ENT_RUNNING:
  138. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  139. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  140. _isHoming = 0;
  141. // Serial.print("target ");
  142. // Serial.println(_targetStep);
  143. stepper->moveTo(_targetStep);
  144. // stepper->computeNewSpeed();
  145. //stepper_update();
  146. //push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  147. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  148. stepper_update();
  149. return;
  150. case LP_RUNNING:
  151. // if on limits and limits are hard, stop moving in one direction
  152. if(limitLow_State && _limitLow_Hard && (stepper->speed()<0.)) {
  153. // Serial.println("youpi");
  154. _currentStep = stepper->currentPosition();
  155. stepper->moveTo(_currentStep);
  156. _targetStep = _currentStep;
  157. stepper->setSpeed(0);
  158. }
  159. if(limitHigh_State && _limitHigh_Hard && ((stepper->speed()>0.))) {
  160. // Serial.println("youpi");
  161. _currentStep = stepper->currentPosition();
  162. stepper->moveTo(_currentStep);
  163. _targetStep = _currentStep;
  164. stepper->setSpeed(0);
  165. }
  166. stepper_update();
  167. if(stepper->speed() == 0.) {trigger(EVT_ON_TARGET);}
  168. return;
  169. case ENT_STOP:
  170. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  171. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  172. if (last_trigger == EVT_STOP) {
  173. runMode = 0 ;
  174. stepper->stop();
  175. _targetStep = stepper->targetPosition();
  176. push( connectors, ON_STOP, 0, 0, 0 );
  177. }
  178. if (last_trigger == EVT_EMERGENCY_STOP) {
  179. stepper->setSpeed(0);
  180. _currentStep = stepper->currentPosition();
  181. _targetStep = _currentStep ;
  182. stepper->moveTo(_targetStep);
  183. push( connectors, ON_STOP, 0, 1, 0 );
  184. }
  185. return;
  186. case LP_STOP:
  187. stepper_update();
  188. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  189. if(stepper->speed() == 0.) {trigger(EVT_ON_TARGET);}
  190. // _currentStep = stepper->currentPosition();
  191. return;
  192. case ENT_HOMING_LOW:
  193. homingLow_done = 0;
  194. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  195. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  196. runMode = 1;
  197. //_isHoming = 1 ;
  198. stepper->setSpeed(-1*homing_speed);
  199. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  200. return;
  201. case LP_HOMING_LOW:
  202. stepper_update();
  203. // if (changed && (limitHigh_State||limitLow_State)){
  204. if(limitLow_State) {
  205. stepper->setCurrentPosition(0);
  206. _currentStep = 0;
  207. homingLow_done = 1 ;
  208. runMode = 0;
  209. trigger(EVT_EMERGENCY_STOP);
  210. push(connectors, ON_ONHOMINGLOW, 0, _currentStep, homingLow_done);
  211. }
  212. else if (changed && limitHigh_State){
  213. homingLow_done = 0 ;
  214. runMode = 0;
  215. trigger(EVT_EMERGENCY_STOP);
  216. push(connectors, ON_ONHOMINGLOW, 0, _currentStep, homingLow_done);
  217. }//Serial.println("homing low failed");}
  218. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  219. //}
  220. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  221. return;
  222. case EXT_HOMING_LOW:
  223. // runMode = 0;
  224. // //_isHoming = 0;
  225. // if(last_trigger == EVT_ON_LIMIT_LOW) {
  226. // stepper->setCurrentPosition(0);
  227. // _currentStep = 0;
  228. // homingLow_done = 1 ;
  229. // }
  230. // else{homingLow_done = 0 ;};//Serial.println("homing low failed");}
  231. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  232. // push(connectors, ON_ONHOMINGLOW, 0, _currentStep, homingLow_done);
  233. // trigger(EVT_EMERGENCY_STOP);
  234. return;
  235. case ENT_HOMING_HIGH:
  236. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  237. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  238. runMode = 1;
  239. //_isHoming = 2 ;
  240. stepper->setSpeed(homing_speed);
  241. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  242. return;
  243. case LP_HOMING_HIGH:
  244. stepper_update();
  245. //if (changed && (limitHigh_State||limitLow_State)){
  246. if(limitHigh_State) {
  247. _maxStep = stepper->currentPosition();
  248. _currentStep = _maxStep;
  249. homingHigh_done = 1;
  250. runMode = 0 ;
  251. trigger(EVT_EMERGENCY_STOP);
  252. push(connectors, ON_ONHOMINGHIGH, 0, _currentStep, homingHigh_done);
  253. //Serial.println("homing high done");
  254. }
  255. else if (changed && limitLow_State){
  256. homingHigh_done = 0;
  257. runMode = 0 ;
  258. trigger(EVT_EMERGENCY_STOP);
  259. push(connectors, ON_ONHOMINGHIGH, 0, _currentStep, homingHigh_done);
  260. }//Serial.println("homing high failed");}
  261. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  262. //stepper_update();
  263. //}
  264. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  265. return;
  266. case EXT_HOMING_HIGH:
  267. //
  268. // runMode = 0;
  269. // //_isHoming = 0;
  270. // if(last_trigger == EVT_ON_LIMIT_HIGH) {
  271. // _maxStep = stepper->currentPosition();
  272. // _currentStep = _maxStep;
  273. //
  274. // homingHigh_done = 1;
  275. // //Serial.println("homing high done");
  276. // }
  277. // else{homingHigh_done = 0;};//Serial.println("homing high failed");}
  278. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  279. // //_targetStep = _currentStep;
  280. // push(connectors, ON_ONHOMINGHIGH, 0, _currentStep, homingHigh_done);
  281. // trigger(EVT_EMERGENCY_STOP);
  282. // return;
  283. case ENT_LIMIT_LOW:
  284. /*triggered by a change in limit state
  285. if state is 0, we may leave this state for running
  286. if state is 1 we stay in limit state loop, where moves are allowed only in
  287. the free direction, until a trigger comes with state 0
  288. */
  289. push( connectors, ON_ONLIMITLOW, 0, limitLow_State, 0 );
  290. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  291. if (!limitLow_State){trigger(EVT_MOVE);}
  292. return;
  293. case LP_LIMIT_LOW:
  294. //stop motor if going down, allow going up
  295. // if(_limitLow_Hard && (_targetStep < _currentStep)) {
  296. if(_limitLow_Hard && (stepper->speed()<0.)) {
  297. // Serial.println("youpi");
  298. _currentStep = stepper->currentPosition();
  299. stepper->moveTo(_currentStep);
  300. _targetStep = _currentStep;
  301. stepper->setSpeed(0);
  302. }
  303. stepper_update();
  304. //else{} // _isHoming ? trigger(EVT_STOP):
  305. return;
  306. case ENT_LIMIT_HIGH:
  307. push( connectors, ON_ONLIMITHIGH, 0, limitHigh_State, 0 );
  308. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  309. if (!limitHigh_State){trigger(EVT_MOVE);};
  310. return;
  311. case LP_LIMIT_HIGH:
  312. //stop motor if going down, allow going up
  313. if(_limitHigh_Hard && ((stepper->speed()>0.))) {
  314. // Serial.println("youpi");
  315. _currentStep = stepper->currentPosition();
  316. stepper->moveTo(_currentStep);
  317. _targetStep = _currentStep;
  318. stepper->setSpeed(0);
  319. }
  320. stepper_update();
  321. // else{}
  322. return;
  323. }
  324. }
  325. /* Optionally override the default trigger() method
  326. * Control how your machine processes triggers
  327. */
  328. Atm_AccelStepper& Atm_AccelStepper::trigger( int event ) {
  329. Machine::trigger( event );
  330. return *this;
  331. }
  332. /* Optionally override the default state() method
  333. * Control what the machine returns when another process requests its state
  334. */
  335. int Atm_AccelStepper::state( void ) {
  336. return Machine::state();
  337. }
  338. /* Nothing customizable below this line
  339. ************************************************************************************************
  340. */
  341. /* Still I'll customize a little just here
  342. */
  343. void Atm_AccelStepper::stepper_update(void) {
  344. switch (runMode) {
  345. case 0: //positional modae
  346. stepper->run();
  347. break;
  348. case 1: // speed mode
  349. stepper->runSpeed();
  350. break;
  351. }
  352. // Serial.print("update ");
  353. // Serial.println(stepper->speed());
  354. long int tempStep = stepper->currentPosition();
  355. if (tempStep != _currentStep){
  356. _currentStep = tempStep;
  357. //Serial.println(stepper->currentPosition());
  358. if (position_timer.expired(this)){
  359. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  360. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  361. }
  362. }
  363. }
  364. Atm_AccelStepper& Atm_AccelStepper::setMaxSpeed( long int maxSpeed){
  365. max_speed = maxSpeed ;
  366. stepper->setMaxSpeed(max_speed);
  367. return *this ;
  368. }
  369. Atm_AccelStepper& Atm_AccelStepper::setHomingSpeed(long int homingSpeed){
  370. homing_speed = homingSpeed ;
  371. return *this ;
  372. }
  373. Atm_AccelStepper& Atm_AccelStepper::setAcceleration(long int acc){
  374. acceleration = acc ;
  375. stepper->setAcceleration(acceleration);
  376. return *this ;
  377. }
  378. Atm_AccelStepper& Atm_AccelStepper::setPosition(long int position){
  379. stepper->setCurrentPosition(position);
  380. _currentStep = position ;
  381. return *this ;
  382. }
  383. long int Atm_AccelStepper::getPosition(){
  384. return stepper->currentPosition();;
  385. }
  386. long int Atm_AccelStepper::distanceToGo(){
  387. return stepper->distanceToGo();;
  388. }
  389. bool Atm_AccelStepper::isRunning(){
  390. return stepper->isRunning();
  391. }
  392. float Atm_AccelStepper::getSpeed(){
  393. return stepper->speed();
  394. }
  395. Atm_AccelStepper& Atm_AccelStepper::position_refresh(long int refresh_ms){
  396. POSITION_SEND_TIMER = refresh_ms ;
  397. return *this ;
  398. }
  399. Atm_AccelStepper& Atm_AccelStepper::move( long int stepRel) {
  400. _targetStep = _currentStep + stepRel;
  401. runMode = 0;
  402. _isHoming = 0;
  403. //Serial.println(_targetStep);
  404. stepper->moveTo(_targetStep);
  405. enable();
  406. trigger( EVT_MOVE );
  407. return *this;
  408. }
  409. Atm_AccelStepper& Atm_AccelStepper::moveTo( long int stepAbs) {
  410. _targetStep = stepAbs;
  411. _isHoming = 0 ;
  412. runMode = 0;
  413. stepper->moveTo(_targetStep);
  414. enable();
  415. trigger( EVT_MOVE );
  416. return *this;
  417. }
  418. Atm_AccelStepper& Atm_AccelStepper::rotate( long int speed) {
  419. runMode = 1;
  420. _isHoming = 0 ;
  421. stepper->setSpeed( speed);
  422. enable();
  423. trigger( EVT_MOVE );
  424. return *this;
  425. }
  426. Atm_AccelStepper& Atm_AccelStepper::homing( bool direction ){
  427. enable();
  428. direction == 1 ? _isHoming = 2 : _isHoming = 1;
  429. direction == 1 ? this->trigger(EVT_HOMING_HIGH) : this->trigger(EVT_HOMING_LOW);
  430. return *this;
  431. }
  432. int Atm_AccelStepper::limitLow_avg(bool limistate){
  433. limitLow_state_total = limitLow_state_total + limistate - limitLow_state_buf[limitLow_buf_head];
  434. limitLow_state_buf[limitLow_buf_head] = limistate;
  435. if ( limitLow_buf_head + 1 >= limit_buf_size ) {
  436. limitLow_buf_head = 0;
  437. } else {
  438. limitLow_buf_head++;
  439. }
  440. // for (int i =0; i<limit_buf_size; i++){
  441. // Serial.print(limitLow_state_buf[i]);
  442. // Serial.print(" ");
  443. // }
  444. // Serial.println();
  445. return limitLow_state_total > limit_buf_size / 2; //all values should agree
  446. }
  447. int Atm_AccelStepper::limitHigh_avg(bool limistate){
  448. limitHigh_state_total = limitHigh_state_total + limistate - limitHigh_state_buf[limitHigh_buf_head];
  449. limitHigh_state_buf[limitHigh_buf_head] = limistate;
  450. if ( limitHigh_buf_head + 1 >= limit_buf_size ) {
  451. limitHigh_buf_head = 0;
  452. } else {
  453. limitHigh_buf_head++;
  454. }
  455. return limitHigh_state_total < limit_buf_size / 2; //all values should agree
  456. }
  457. // Atm_AccelStepper& Atm_AccelStepper::rotationReversed(bool reversed){
  458. // _rotationReversed = reversed ? -1 : 1 ;
  459. // }
  460. Atm_AccelStepper& Atm_AccelStepper::setEnablePin( int enablePin ){
  461. _enablePin = enablePin ;
  462. pinMode(_enablePin, OUTPUT);
  463. return *this;
  464. }
  465. Atm_AccelStepper& Atm_AccelStepper::pinReversed( bool directionInvert,
  466. bool stepInvert, bool enableInvert){
  467. stepper->setPinsInverted(directionInvert, stepInvert, enableInvert);
  468. return *this;
  469. }
  470. Atm_AccelStepper& Atm_AccelStepper::limitLow_set(int mode, int pin, int reversed){
  471. _limitLow_Mode = mode ;
  472. _limitLow_Pin = pin ;
  473. _limitLow_Reversed = reversed ;
  474. if (_limitLow_Mode==1) {pinMode(_limitLow_Pin, INPUT_PULLUP);}
  475. if (_limitLow_Mode==2) {pinMode(_limitLow_Pin, INPUT);}
  476. return *this;
  477. }
  478. Atm_AccelStepper& Atm_AccelStepper::limitLow_isHard(bool hardlimit){
  479. _limitLow_Hard = hardlimit;
  480. return *this;
  481. }
  482. Atm_AccelStepper& Atm_AccelStepper::limitLow_setThresholds (int threshold_low, int threshold_high){
  483. _limitLow_Thresholds[0] = threshold_low ;
  484. _limitLow_Thresholds[1] = threshold_high ;
  485. return *this;
  486. }
  487. Atm_AccelStepper& Atm_AccelStepper::limitHigh_set(int mode, int pin, int reversed){
  488. _limitHigh_Mode = mode ;
  489. _limitHigh_Pin = pin ;
  490. _limitHigh_Reversed = reversed ;
  491. if (_limitHigh_Mode==1) {pinMode(_limitHigh_Pin, INPUT_PULLUP);}
  492. if (_limitHigh_Mode==2) {pinMode(_limitHigh_Pin, INPUT);}
  493. return *this;
  494. }
  495. Atm_AccelStepper& Atm_AccelStepper::limitHigh_isHard(bool hardlimit){
  496. _limitHigh_Hard = hardlimit;
  497. return *this;
  498. }
  499. Atm_AccelStepper& Atm_AccelStepper::limitHigh_setThresholds (int threshold_low, int threshold_high){
  500. _limitHigh_Thresholds[0] = threshold_low ;
  501. _limitHigh_Thresholds[1] = threshold_high ;
  502. return *this;
  503. }
  504. /* Public event methods
  505. *
  506. */
  507. Atm_AccelStepper& Atm_AccelStepper::disable() {
  508. trigger( EVT_DISABLE );
  509. return *this;
  510. }
  511. Atm_AccelStepper& Atm_AccelStepper::enable() {
  512. trigger( EVT_ENABLE );
  513. return *this;
  514. }
  515. // Atm_AccelStepper& Atm_AccelStepper::move() {
  516. // trigger( EVT_MOVE );
  517. // return *this;
  518. // }
  519. Atm_AccelStepper& Atm_AccelStepper::stop() {
  520. trigger( EVT_STOP );
  521. return *this;
  522. }
  523. Atm_AccelStepper& Atm_AccelStepper::emergency_stop() {
  524. trigger( EVT_EMERGENCY_STOP );
  525. return *this;
  526. }
  527. Atm_AccelStepper& Atm_AccelStepper::on_limit_low() {
  528. trigger( EVT_ON_LIMIT_LOW );
  529. return *this;
  530. }
  531. Atm_AccelStepper& Atm_AccelStepper::on_limit_high() {
  532. trigger( EVT_ON_LIMIT_HIGH );
  533. return *this;
  534. }
  535. Atm_AccelStepper& Atm_AccelStepper::on_target() {
  536. trigger( EVT_ON_TARGET );
  537. return *this;
  538. }
  539. /*
  540. * onChangeposition() push connector variants ( slots 1, autostore 0, broadcast 0 )
  541. */
  542. Atm_AccelStepper& Atm_AccelStepper::onChangeposition( Machine& machine, int event ) {
  543. onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, machine, event );
  544. return *this;
  545. }
  546. Atm_AccelStepper& Atm_AccelStepper::onChangeposition( atm_cb_push_t callback, int idx ) {
  547. onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, callback, idx );
  548. return *this;
  549. }
  550. /*
  551. * onChangestate() push connector variants ( slots 1, autostore 0, broadcast 0 )
  552. */
  553. Atm_AccelStepper& Atm_AccelStepper::onChangestate( Machine& machine, int event ) {
  554. onPush( connectors, ON_CHANGESTATE, 0, 1, 1, machine, event );
  555. return *this;
  556. }
  557. Atm_AccelStepper& Atm_AccelStepper::onChangestate( atm_cb_push_t callback, int idx ) {
  558. onPush( connectors, ON_CHANGESTATE, 0, 1, 1, callback, idx );
  559. return *this;
  560. }
  561. /*
  562. * onOnlimithigh() push connector variants ( slots 1, autostore 0, broadcast 0 )
  563. */
  564. Atm_AccelStepper& Atm_AccelStepper::onOnlimithigh( Machine& machine, int event ) {
  565. onPush( connectors, ON_ONLIMITHIGH, 0, 1, 1, machine, event );
  566. return *this;
  567. }
  568. Atm_AccelStepper& Atm_AccelStepper::onOnlimithigh( atm_cb_push_t callback, int idx ) {
  569. onPush( connectors, ON_ONLIMITHIGH, 0, 1, 1, callback, idx );
  570. return *this;
  571. }
  572. /*
  573. * onOnlimitlow() push connector variants ( slots 1, autostore 0, broadcast 0 )
  574. */
  575. Atm_AccelStepper& Atm_AccelStepper::onOnlimitlow( Machine& machine, int event ) {
  576. onPush( connectors, ON_ONLIMITLOW, 0, 1, 1, machine, event );
  577. return *this;
  578. }
  579. Atm_AccelStepper& Atm_AccelStepper::onOnlimitlow( atm_cb_push_t callback, int idx ) {
  580. onPush( connectors, ON_ONLIMITLOW, 0, 1, 1, callback, idx );
  581. return *this;
  582. }
  583. /*
  584. * onOntarget() push connector variants ( slots 1, autostore 0, broadcast 0 )
  585. */
  586. Atm_AccelStepper& Atm_AccelStepper::onOntarget( Machine& machine, int event ) {
  587. onPush( connectors, ON_ONTARGET, 0, 1, 1, machine, event );
  588. return *this;
  589. }
  590. Atm_AccelStepper& Atm_AccelStepper::onOntarget( atm_cb_push_t callback, int idx ) {
  591. onPush( connectors, ON_ONTARGET, 0, 1, 1, callback, idx );
  592. return *this;
  593. }
  594. /*
  595. * onStop() push connector variants ( slots 1, autostore 0, broadcast 0 )
  596. */
  597. Atm_AccelStepper& Atm_AccelStepper::onStop( Machine& machine, int event ) {
  598. onPush( connectors, ON_STOP, 0, 1, 1, machine, event );
  599. return *this;
  600. }
  601. Atm_AccelStepper& Atm_AccelStepper::onStop( atm_cb_push_t callback, int idx ) {
  602. onPush( connectors, ON_STOP, 0, 1, 1, callback, idx );
  603. return *this;
  604. }
  605. Atm_AccelStepper& Atm_AccelStepper::onOnhominglow( Machine& machine, int event ) {
  606. onPush( connectors, ON_ONHOMINGLOW, 0, 1, 1, machine, event );
  607. return *this;
  608. }
  609. Atm_AccelStepper& Atm_AccelStepper::onOnhominglow( atm_cb_push_t callback, int idx ) {
  610. onPush( connectors, ON_ONHOMINGLOW, 0, 1, 1, callback, idx );
  611. return *this;
  612. }
  613. Atm_AccelStepper& Atm_AccelStepper::onOnhominghigh( Machine& machine, int event ) {
  614. onPush( connectors, ON_ONHOMINGHIGH, 0, 1, 1, machine, event );
  615. return *this;
  616. }
  617. Atm_AccelStepper& Atm_AccelStepper::onOnhominghigh( atm_cb_push_t callback, int idx ) {
  618. onPush( connectors, ON_ONHOMINGHIGH, 0, 1, 1, callback, idx );
  619. return *this;
  620. }
  621. /* State trace method
  622. * Sets the symbol table and the default logging method for serial monitoring
  623. */
  624. Atm_AccelStepper& Atm_AccelStepper::trace( Stream & stream ) {
  625. Machine::setTrace( &stream, atm_serial_debug::trace,
  626. "ACCELSTEPPER\0EVT_DISABLE\0EVT_ENABLE\0EVT_ENABLED_TIMEOUT\0EVT_MOVE\0EVT_STOP\0EVT_EMERGENCY_STOP\0EVT_ON_LIMIT_LOW\0EVT_ON_LIMIT_HIGH\0EVT_ON_TARGET\0EVT_HOMING_LOW\0EVT_HOMING_HIGH\0ELSE\0DISABLED\0ENABLED\0RUNNING\0STOP\0HOMING_LOW\0HOMING_HIGH\0LIMIT_LOW\0LIMIT_HIGH" );
  627. return *this;
  628. }