Atm_AccelStepper.cpp 26 KB

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