Atm_AccelStepper.cpp 26 KB

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