Atm_AccelStepper.cpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772
  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, ENABLED, -1, -1, -1,
  13. /* STOP */ ENT_STOP, LP_STOP, -1, DISABLE, ENABLED, -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; //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, stepper->currentPosition(), _currentSpeed);
  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 && (_currentSpeed<0.)) {
  161. trigger(EVT_EMERGENCY_STOP);
  162. }
  163. if( limitHigh_State && _limitHigh_Hard && (_currentSpeed>0.)) {
  164. trigger(EVT_EMERGENCY_STOP);
  165. }
  166. // if hard limits and homing is done, check current position is within limits
  167. if (_limitLow_Hard && homingLow_done) {
  168. if( (_currentStep<0) && (_currentSpeed<0.)) {trigger(EVT_EMERGENCY_STOP);}
  169. }
  170. if (_limitHigh_Hard && _maxStep) { //maxstep is 0 if not defined
  171. if( (_currentStep>_maxStep) && (_currentSpeed>0.)) {trigger(EVT_EMERGENCY_STOP);}
  172. }
  173. stepper_update();
  174. if(runMode && _currentSpeed == 0.) {trigger(EVT_EMERGENCY_STOP);}//trigger(EVT_ON_TARGET);
  175. if(!runMode && (_currentStep==_targetStep)){push( connectors, ON_ONTARGET, 0, _currentStep, 0 );trigger(EVT_EMERGENCY_STOP);}
  176. return;
  177. case ENT_STOP:
  178. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  179. if (last_trigger == EVT_STOP) {
  180. runMode = 0 ;
  181. // stepper->setSpeed(stepper->speed());
  182. // stepper_update();
  183. stepper->stop();
  184. _targetStep = stepper->targetPosition();
  185. // push( connectors, ON_STOP, 0, 0, 0 );
  186. }
  187. if (last_trigger == EVT_EMERGENCY_STOP) {
  188. runMode=0 ;
  189. stepper->setSpeed(0);
  190. _currentStep = stepper->currentPosition();
  191. _targetStep = _currentStep ;
  192. stepper->setCurrentPosition(_currentStep);
  193. // stepper->moveTo(_targetStep);
  194. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  195. // push( connectors, ON_STOP, 0, 1, 0 );
  196. }
  197. stepper_update();
  198. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  199. return;
  200. case LP_STOP:
  201. stepper_update();
  202. if(_currentSpeed == 0.) {trigger(EVT_ENABLE);}
  203. return;
  204. case ENT_HOMING_LOW:
  205. homingLow_done = 0;
  206. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  207. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, _currentSpeed);
  208. runMode = 1;
  209. //_isHoming = 1 ;
  210. stepper->setSpeed(-1*homing_speed);
  211. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  212. limits_timer.setFromNow(this, LIMIT_UPDATE_RATE);
  213. return;
  214. case LP_HOMING_LOW:
  215. stepper_update();
  216. // if (changed && (limitHigh_State||limitLow_State)){
  217. if(limitLow_State) {
  218. stepper->setCurrentPosition(0);
  219. _currentStep = 0;
  220. homingLow_done = 1 ;
  221. runMode = 0;
  222. trigger(EVT_EMERGENCY_STOP);
  223. push(connectors, ON_ONHOMINGLOW, 0, _currentStep, homingLow_done);
  224. }
  225. else if (changed && limitHigh_State ){
  226. homingLow_done = 0 ;
  227. runMode = 0;
  228. trigger(EVT_EMERGENCY_STOP);
  229. push(connectors, ON_ONHOMINGLOW, 0, _currentStep, homingLow_done);
  230. }//Serial.println("homing low failed");}
  231. return;
  232. case EXT_HOMING_LOW:
  233. // runMode = 0;
  234. // //_isHoming = 0;
  235. // if(last_trigger == EVT_ON_LIMIT_LOW) {
  236. // stepper->setCurrentPosition(0);
  237. // _currentStep = 0;
  238. // homingLow_done = 1 ;
  239. // }
  240. // else{homingLow_done = 0 ;};//Serial.println("homing low failed");}
  241. // push(connectors, ON_CHANGEPOSITION, 0, _currentStep, stepper->speed());
  242. // push(connectors, ON_ONHOMINGLOW, 0, _currentStep, homingLow_done);
  243. // trigger(EVT_EMERGENCY_STOP);
  244. return;
  245. case ENT_HOMING_HIGH:
  246. push(connectors, ON_CHANGESTATE, 0, state(), 0);
  247. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, _currentSpeed);
  248. runMode = 1;
  249. //_isHoming = 2 ;
  250. stepper->setSpeed(homing_speed);
  251. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  252. limits_timer.setFromNow(this, LIMIT_UPDATE_RATE);
  253. return;
  254. case LP_HOMING_HIGH:
  255. stepper_update();
  256. //if (changed && (limitHigh_State||limitLow_State)){
  257. if(limitHigh_State) {
  258. _maxStep = stepper->currentPosition();
  259. _currentStep = _maxStep;
  260. homingHigh_done = 1;
  261. runMode = 0 ;
  262. trigger(EVT_EMERGENCY_STOP);
  263. push(connectors, ON_ONHOMINGHIGH, 0, _currentStep, homingHigh_done);
  264. //Serial.println("homing high done");
  265. }
  266. else if (changed && limitLow_State ){
  267. homingHigh_done = 0;
  268. runMode = 0 ;
  269. trigger(EVT_EMERGENCY_STOP);
  270. push(connectors, ON_ONHOMINGHIGH, 0, _currentStep, homingHigh_done);
  271. }//Serial.println("homing high failed");}
  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, _currentSpeed);
  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, _currentSpeed);
  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 && (_currentSpeed>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. _currentSpeed = stepper->speed();
  360. long int tempStep = stepper->currentPosition();
  361. if (tempStep != _currentStep){
  362. _currentStep = tempStep;
  363. //Serial.println(stepper->currentPosition());
  364. if (position_timer.expired(this)){
  365. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, _currentSpeed);
  366. position_timer.setFromNow(this, POSITION_SEND_TIMER);
  367. }
  368. }
  369. }
  370. Atm_AccelStepper& Atm_AccelStepper::setMaxStep( long int maxStep ) {
  371. _maxStep = maxStep;
  372. return *this ;
  373. }
  374. Atm_AccelStepper& Atm_AccelStepper::setMaxSpeed( long int maxSpeed){
  375. max_speed = maxSpeed ;
  376. stepper->setMaxSpeed(max_speed);
  377. return *this ;
  378. }
  379. Atm_AccelStepper& Atm_AccelStepper::setHomingSpeed(long int homingSpeed){
  380. homing_speed = homingSpeed ;
  381. return *this ;
  382. }
  383. Atm_AccelStepper& Atm_AccelStepper::setAcceleration(long int acc){
  384. acceleration = acc ;
  385. stepper->setAcceleration(acceleration);
  386. return *this ;
  387. }
  388. Atm_AccelStepper& Atm_AccelStepper::setPosition(long int position){
  389. stepper->setCurrentPosition(position);
  390. _currentStep = position ;
  391. return *this ;
  392. }
  393. long int Atm_AccelStepper::getPosition(){
  394. return stepper->currentPosition();;
  395. }
  396. long int Atm_AccelStepper::distanceToGo(){
  397. return stepper->distanceToGo();;
  398. }
  399. bool Atm_AccelStepper::isRunning(){
  400. return stepper->isRunning();
  401. }
  402. float Atm_AccelStepper::getSpeed(){
  403. return stepper->speed();
  404. }
  405. Atm_AccelStepper& Atm_AccelStepper::position_refresh(long int refresh_ms){
  406. POSITION_SEND_TIMER = refresh_ms ;
  407. return *this ;
  408. }
  409. Atm_AccelStepper& Atm_AccelStepper::move( long int stepRel) {
  410. _targetStep = _currentStep + stepRel;
  411. runMode = 0;
  412. // _isHoming = 0;
  413. //Serial.println(_targetStep);
  414. stepper->moveTo(_targetStep);
  415. enable();
  416. trigger( EVT_MOVE );
  417. return *this;
  418. }
  419. Atm_AccelStepper& Atm_AccelStepper::moveTo( long int stepAbs) {
  420. _targetStep = stepAbs;
  421. // _isHoming = 0 ;
  422. runMode = 0;
  423. stepper->moveTo(_targetStep);
  424. enable();
  425. trigger( EVT_MOVE );
  426. return *this;
  427. }
  428. Atm_AccelStepper& Atm_AccelStepper::movePercent( float percent) {
  429. // Serial.println(percent/100.)
  430. _targetStep = (float)_currentStep + percent/100.*float(_maxStep);
  431. runMode = 0;
  432. // _isHoming = 0;
  433. Serial.println(_targetStep);
  434. stepper->moveTo(_targetStep);
  435. enable();
  436. trigger( EVT_MOVE );
  437. return *this;
  438. }
  439. Atm_AccelStepper& Atm_AccelStepper::moveToPercent( float percent) {
  440. _targetStep = (float) percent/100*float(_maxStep) ;
  441. // _isHoming = 0
  442. runMode = 0;
  443. stepper->moveTo(_targetStep);
  444. enable();
  445. trigger( EVT_MOVE );
  446. return *this;
  447. }
  448. Atm_AccelStepper& Atm_AccelStepper::rotate( long int speed) {
  449. runMode = 1;
  450. // _isHoming = 0 ;
  451. stepper->setSpeed( speed);
  452. stepper->runSpeed();
  453. enable();
  454. trigger( EVT_MOVE );
  455. return *this;
  456. }
  457. Atm_AccelStepper& Atm_AccelStepper::homing( bool direction ){
  458. enable();
  459. // direction == 1 ? _isHoming = 2 : _isHoming = 1;
  460. direction == 1 ? this->trigger(EVT_HOMING_HIGH) : this->trigger(EVT_HOMING_LOW);
  461. return *this;
  462. }
  463. int Atm_AccelStepper::limitLow_avg(bool limistate){
  464. limitLow_state_total = limitLow_state_total + limistate - limitLow_state_buf[limitLow_buf_head];
  465. limitLow_state_buf[limitLow_buf_head] = limistate;
  466. if ( limitLow_buf_head + 1 >= limit_buf_size ) {
  467. limitLow_buf_head = 0;
  468. } else {
  469. limitLow_buf_head++;
  470. }
  471. // for (int i =0; i<limit_buf_size; i++){
  472. // Serial.print(limitLow_state_buf[i]);
  473. // Serial.print(" ");
  474. // }
  475. // Serial.println();
  476. return limitLow_state_total > limit_buf_size / 2; //all values should agree
  477. }
  478. int Atm_AccelStepper::limitHigh_avg(bool limistate){
  479. limitHigh_state_total = limitHigh_state_total + limistate - limitHigh_state_buf[limitHigh_buf_head];
  480. limitHigh_state_buf[limitHigh_buf_head] = limistate;
  481. if ( limitHigh_buf_head + 1 >= limit_buf_size ) {
  482. limitHigh_buf_head = 0;
  483. } else {
  484. limitHigh_buf_head++;
  485. }
  486. return limitHigh_state_total > limit_buf_size / 2; //all values should agree
  487. }
  488. // Atm_AccelStepper& Atm_AccelStepper::rotationReversed(bool reversed){
  489. // _rotationReversed = reversed ? -1 : 1 ;
  490. // }
  491. Atm_AccelStepper& Atm_AccelStepper::setEnablePin( int enablePin ){
  492. _enablePin = enablePin ;
  493. pinMode(_enablePin, OUTPUT);
  494. return *this;
  495. }
  496. Atm_AccelStepper& Atm_AccelStepper::pinReversed( bool directionInvert,
  497. bool stepInvert, bool enableInvert){
  498. stepper->setPinsInverted(directionInvert, stepInvert, enableInvert);
  499. return *this;
  500. }
  501. Atm_AccelStepper& Atm_AccelStepper::limitLow_set(int mode, int pin, int reversed){
  502. _limitLow_Mode = mode ;
  503. _limitLow_Pin = pin ;
  504. _limitLow_Reversed = reversed ;
  505. if (_limitLow_Mode==1) {pinMode(_limitLow_Pin, INPUT_PULLUP);}
  506. if (_limitLow_Mode==2) {pinMode(_limitLow_Pin, INPUT);}
  507. return *this;
  508. }
  509. Atm_AccelStepper& Atm_AccelStepper::limitLow_isHard(bool hardlimit){
  510. _limitLow_Hard = hardlimit;
  511. return *this;
  512. }
  513. Atm_AccelStepper& Atm_AccelStepper::limitLow_setThresholds (int threshold_low, int threshold_high){
  514. _limitLow_Thresholds[0] = threshold_low ;
  515. _limitLow_Thresholds[1] = threshold_high ;
  516. return *this;
  517. }
  518. Atm_AccelStepper& Atm_AccelStepper::limitHigh_set(int mode, int pin, int reversed){
  519. _limitHigh_Mode = mode ;
  520. _limitHigh_Pin = pin ;
  521. _limitHigh_Reversed = reversed ;
  522. if (_limitHigh_Mode==1) {pinMode(_limitHigh_Pin, INPUT_PULLUP);}
  523. if (_limitHigh_Mode==2) {pinMode(_limitHigh_Pin, INPUT);}
  524. return *this;
  525. }
  526. Atm_AccelStepper& Atm_AccelStepper::limitHigh_isHard(bool hardlimit){
  527. _limitHigh_Hard = hardlimit;
  528. return *this;
  529. }
  530. Atm_AccelStepper& Atm_AccelStepper::limitHigh_setThresholds (int threshold_low, int threshold_high){
  531. _limitHigh_Thresholds[0] = threshold_low ;
  532. _limitHigh_Thresholds[1] = threshold_high ;
  533. return *this;
  534. }
  535. /* Public event methods
  536. *
  537. */
  538. Atm_AccelStepper& Atm_AccelStepper::disable() {
  539. trigger( EVT_DISABLE );
  540. return *this;
  541. }
  542. Atm_AccelStepper& Atm_AccelStepper::enable() {
  543. trigger( EVT_ENABLE );
  544. return *this;
  545. }
  546. // Atm_AccelStepper& Atm_AccelStepper::move() {
  547. // trigger( EVT_MOVE );
  548. // return *this;
  549. // }
  550. Atm_AccelStepper& Atm_AccelStepper::stop() {
  551. trigger( EVT_STOP );
  552. return *this;
  553. }
  554. Atm_AccelStepper& Atm_AccelStepper::emergency_stop() {
  555. trigger( EVT_EMERGENCY_STOP );
  556. return *this;
  557. }
  558. Atm_AccelStepper& Atm_AccelStepper::on_limit_low() {
  559. trigger( EVT_ON_LIMIT_LOW );
  560. return *this;
  561. }
  562. Atm_AccelStepper& Atm_AccelStepper::on_limit_high() {
  563. trigger( EVT_ON_LIMIT_HIGH );
  564. return *this;
  565. }
  566. Atm_AccelStepper& Atm_AccelStepper::on_target() {
  567. trigger( EVT_ON_TARGET );
  568. return *this;
  569. }
  570. /*
  571. * onChangeposition() push connector variants ( slots 1, autostore 0, broadcast 0 )
  572. */
  573. Atm_AccelStepper& Atm_AccelStepper::onChangeposition( Machine& machine, int event ) {
  574. onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, machine, event );
  575. return *this;
  576. }
  577. Atm_AccelStepper& Atm_AccelStepper::onChangeposition( atm_cb_push_t callback, int idx ) {
  578. onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, callback, idx );
  579. return *this;
  580. }
  581. /*
  582. * onChangestate() push connector variants ( slots 1, autostore 0, broadcast 0 )
  583. */
  584. Atm_AccelStepper& Atm_AccelStepper::onChangestate( Machine& machine, int event ) {
  585. onPush( connectors, ON_CHANGESTATE, 0, 1, 1, machine, event );
  586. return *this;
  587. }
  588. Atm_AccelStepper& Atm_AccelStepper::onChangestate( atm_cb_push_t callback, int idx ) {
  589. onPush( connectors, ON_CHANGESTATE, 0, 1, 1, callback, idx );
  590. return *this;
  591. }
  592. /*
  593. * onOnlimithigh() push connector variants ( slots 1, autostore 0, broadcast 0 )
  594. */
  595. Atm_AccelStepper& Atm_AccelStepper::onOnlimithigh( Machine& machine, int event ) {
  596. onPush( connectors, ON_ONLIMITHIGH, 0, 1, 1, machine, event );
  597. return *this;
  598. }
  599. Atm_AccelStepper& Atm_AccelStepper::onOnlimithigh( atm_cb_push_t callback, int idx ) {
  600. onPush( connectors, ON_ONLIMITHIGH, 0, 1, 1, callback, idx );
  601. return *this;
  602. }
  603. /*
  604. * onOnlimitlow() push connector variants ( slots 1, autostore 0, broadcast 0 )
  605. */
  606. Atm_AccelStepper& Atm_AccelStepper::onOnlimitlow( Machine& machine, int event ) {
  607. onPush( connectors, ON_ONLIMITLOW, 0, 1, 1, machine, event );
  608. return *this;
  609. }
  610. Atm_AccelStepper& Atm_AccelStepper::onOnlimitlow( atm_cb_push_t callback, int idx ) {
  611. onPush( connectors, ON_ONLIMITLOW, 0, 1, 1, callback, idx );
  612. return *this;
  613. }
  614. /*
  615. * onOntarget() push connector variants ( slots 1, autostore 0, broadcast 0 )
  616. */
  617. Atm_AccelStepper& Atm_AccelStepper::onOntarget( Machine& machine, int event ) {
  618. onPush( connectors, ON_ONTARGET, 0, 1, 1, machine, event );
  619. return *this;
  620. }
  621. Atm_AccelStepper& Atm_AccelStepper::onOntarget( atm_cb_push_t callback, int idx ) {
  622. onPush( connectors, ON_ONTARGET, 0, 1, 1, callback, idx );
  623. return *this;
  624. }
  625. /*
  626. * onStop() push connector variants ( slots 1, autostore 0, broadcast 0 )
  627. */
  628. Atm_AccelStepper& Atm_AccelStepper::onStop( Machine& machine, int event ) {
  629. onPush( connectors, ON_STOP, 0, 1, 1, machine, event );
  630. return *this;
  631. }
  632. Atm_AccelStepper& Atm_AccelStepper::onStop( atm_cb_push_t callback, int idx ) {
  633. onPush( connectors, ON_STOP, 0, 1, 1, callback, idx );
  634. return *this;
  635. }
  636. Atm_AccelStepper& Atm_AccelStepper::onOnhominglow( Machine& machine, int event ) {
  637. onPush( connectors, ON_ONHOMINGLOW, 0, 1, 1, machine, event );
  638. return *this;
  639. }
  640. Atm_AccelStepper& Atm_AccelStepper::onOnhominglow( atm_cb_push_t callback, int idx ) {
  641. onPush( connectors, ON_ONHOMINGLOW, 0, 1, 1, callback, idx );
  642. return *this;
  643. }
  644. Atm_AccelStepper& Atm_AccelStepper::onOnhominghigh( Machine& machine, int event ) {
  645. onPush( connectors, ON_ONHOMINGHIGH, 0, 1, 1, machine, event );
  646. return *this;
  647. }
  648. Atm_AccelStepper& Atm_AccelStepper::onOnhominghigh( atm_cb_push_t callback, int idx ) {
  649. onPush( connectors, ON_ONHOMINGHIGH, 0, 1, 1, callback, idx );
  650. return *this;
  651. }
  652. /* State trace method
  653. * Sets the symbol table and the default logging method for serial monitoring
  654. */
  655. Atm_AccelStepper& Atm_AccelStepper::trace( Stream & stream ) {
  656. Machine::setTrace( &stream, atm_serial_debug::trace,
  657. "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" );
  658. return *this;
  659. }
  660. // #endif