Atm_AccelStepper.cpp 26 KB

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