Atm_Tstepper.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520
  1. #include "Atm_Tstepper.h"
  2. /* Add optional parameters for the state machine to begin()
  3. * Add extra initialization code
  4. */
  5. Atm_Tstepper& Atm_Tstepper::begin(Stepper & motorRef, StepControl & stepControlRef) {
  6. // clang-format off
  7. const static state_t state_table[] PROGMEM = {
  8. /* ON_ENTER ON_LOOP ON_EXIT EVT_HOMING_COUNTER EVT_IDLE_TIMEOUT EVT_MOVE_TIMEOUT EVT_LIMIT_LOW EVT_LIMIT_HIGH EVT_EMERGENCY EVT_STOP EVT_ONTARGET EVT_MOVE EVT_DISABLE EVT_ENABLE EVT_HOMING ELSE */
  9. /* DISABLED */ ENT_DISABLED, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, ENABLED, -1, -1,
  10. /* ENABLED */ ENT_ENABLED, -1, -1, -1, DISABLED, -1, -1, -1, -1, -1, -1, RUNNING, DISABLED, -1, HOMING, -1,
  11. /* RUNNING */ ENT_RUNNING, LP_RUNNING, -1, -1, -1, MOVE_TIMEOUT, EMERGENCY, EMERGENCY, EMERGENCY, STOPPING, ENABLED, RUNNING, -1, -1, -1, -1,
  12. /* STOPPING */ ENT_STOPPING, LP_STOPPING, -1, -1, -1, -1, EMERGENCY, EMERGENCY, EMERGENCY, -1, -1, RUNNING, -1, -1, -1, -1,
  13. /* EMERGENCY */ ENT_EMERGENCY, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1,
  14. /* HOMING */ ENT_HOMING, LP_HOMING, EXT_HOMING, -1, -1, MOVE_TIMEOUT, EMERGENCY, EMERGENCY, EMERGENCY, STOPPING, MOVE_TIMEOUT, -1, -1, -1, -1, -1,
  15. /* MOVE_TIMEOUT */ ENT_MOVE_TIMEOUT, -1, -1, -1, -1, -1, EMERGENCY, -1, EMERGENCY, -1, -1, -1, -1, -1, -1, -1,
  16. /* HOMING_COUNTEROUT */ -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1
  17. };
  18. // clang-format on
  19. Machine::begin( state_table, ELSE );
  20. this-> motor = &motorRef;
  21. this-> controller = &stepControlRef;
  22. idle_timer.set(ATM_TIMER_OFF);
  23. moving_timer.set(ATM_TIMER_OFF);
  24. return *this;
  25. }
  26. /* Add C++ code for each internally handled event (input)
  27. * The code must return 1 to trigger the event
  28. */
  29. int Atm_Tstepper::event( int id ) {
  30. switch ( id ) {
  31. case EVT_HOMING_COUNTER:
  32. return 0;
  33. case EVT_IDLE_TIMEOUT:
  34. return idle_timer.expired(this);
  35. case EVT_MOVE_TIMEOUT:
  36. return moving_timer.expired(this);
  37. case EVT_LIMIT_LOW:
  38. return limitState[0];//limitState[0];
  39. case EVT_LIMIT_HIGH:
  40. return limitState[1];///limitState[1];
  41. case EVT_EMERGENCY:
  42. return 0;
  43. case EVT_STOP:
  44. return 0;
  45. case EVT_ONTARGET: //triggers if stepper reached _targetStep
  46. return _currentStep == _targetStep ;
  47. case EVT_MOVE:
  48. return 0;
  49. case EVT_DISABLE:
  50. return 0;
  51. case EVT_ENABLE:
  52. return 0;
  53. case EVT_HOMING:
  54. return 0;
  55. }
  56. return 0;
  57. }
  58. /* Add C++ code for each action
  59. * This generates the 'output' for the state machine
  60. *
  61. * Available connectors:
  62. * push( connectors, ON_ONCHANGE, 0, <v>, <up> );
  63. * push( connectors, ON_ONCHANGEACCELERATION, 0, <v>, <up> );
  64. * push( connectors, ON_ONCHANGEPOSITION, 0, <v>, <up> );
  65. * push( connectors, ON_ONCHANGESTATE, 0, <v>, <up> );
  66. * push( connectors, ON_ONHIGHLIMIT, 0, <v>, <up> );
  67. * push( connectors, ON_ONHOMINGCOUNTEROUT, 0, <v>, <up> );
  68. * push( connectors, ON_ONHOMINGTIMEOUT, 0, <v>, <up> );
  69. * push( connectors, ON_ONIDLETIMEOUT, 0, <v>, <up> );
  70. * push( connectors, ON_ONLOWLIMIT, 0, <v>, <up> );
  71. * push( connectors, ON_ONMOVETIMEOUT, 0, <v>, <up> );
  72. * push( connectors, ON_SPEED, 0, <v>, <up> );
  73. */
  74. void Atm_Tstepper::action( int id ) {
  75. switch ( id ) {
  76. long int tempStep ;
  77. case ENT_DISABLED:
  78. idle_timer.set(ATM_TIMER_OFF);
  79. moving_timer.set(ATM_TIMER_OFF);
  80. enabled = _enableReversed ? HIGH : LOW;
  81. digitalWrite(_enablePin, enabled);
  82. sendOSC();
  83. return;
  84. case ENT_ENABLED:
  85. // idle_timer.set(IDLE_TIMEOUT_DURATION);
  86. // moving_timer.set(ATM_TIMER_OFF);
  87. enabled = _enableReversed ? LOW : HIGH ;
  88. digitalWrite(_enablePin, enabled);
  89. sendOSC();
  90. return;
  91. case ENT_RUNNING:
  92. // idle_timer.set(ATM_TIMER_OFF);
  93. // moving_timer.set(MOVING_TIMEOUT_DURATION);
  94. return;
  95. case LP_RUNNING:
  96. tempStep = motor->getPosition();
  97. connectors[ON_ONCHANGEPOSITION].push(_currentStep);
  98. // if (tempStep != _currentStep){push( connectors, ON_ONCHANGEPOSITION, 0, _currentStep, 0 );} ;
  99. _currentStep = tempStep;
  100. updateLimitSwitch();
  101. sendOSC();
  102. return;
  103. case ENT_STOPPING:
  104. idle_timer.set(ATM_TIMER_OFF);
  105. moving_timer.set(ATM_TIMER_OFF);
  106. sendOSC();
  107. return;
  108. case LP_STOPPING:
  109. return;
  110. case ENT_EMERGENCY:
  111. idle_timer.set(ATM_TIMER_OFF);
  112. moving_timer.set(ATM_TIMER_OFF);
  113. controller->emergencyStop();
  114. sendOSC();
  115. return;
  116. case ENT_HOMING:
  117. // idle_timer.set(ATM_TIMER_OFF);
  118. // moving_timer.set(MOVING_TIMEOUT_DURATION);
  119. _limitType ? move(-2147483647) : trigger(EVT_STOP) ;
  120. sendOSC();
  121. return;
  122. case LP_HOMING:
  123. updateLimitSwitch();
  124. sendOSC();
  125. return;
  126. case EXT_HOMING:
  127. switch(next_trigger){
  128. case EVT_LIMIT_LOW:
  129. Serial.println("LOW");
  130. move(10);
  131. return;
  132. case EVT_LIMIT_HIGH:
  133. Serial.println("HIGH");
  134. move(-10);
  135. return;
  136. }
  137. return;
  138. case ENT_MOVE_TIMEOUT:
  139. idle_timer.set(ATM_TIMER_OFF);
  140. moving_timer.set(ATM_TIMER_OFF);
  141. emergency();
  142. return;
  143. }
  144. }
  145. /* Optionally override the default trigger() method
  146. * Control how your machine processes triggers
  147. */
  148. Atm_Tstepper& Atm_Tstepper::trigger( int event ) {
  149. Machine::trigger( event );
  150. return *this;
  151. }
  152. /* Optionally override the default state() method
  153. * Control what the machine returns when another process requests its state
  154. */
  155. int Atm_Tstepper::state( void ) {
  156. return Machine::state();
  157. }
  158. /* CUSTOM METHODS
  159. ********************************************************************************************************
  160. */
  161. // Atm_TeensyStep& Atm_TeensyStep::enable( bool enable ){
  162. //
  163. // return *this;
  164. // }
  165. ///////// ENABLE/DISABLE ////////
  166. Atm_Tstepper& Atm_Tstepper::setEnablePin( int enablePin ){
  167. _enablePin = enablePin ;
  168. pinMode(_enablePin, OUTPUT);
  169. return *this;
  170. }
  171. Atm_Tstepper& Atm_Tstepper::enableReversed( bool reverse ){
  172. _enableReversed = reverse ;
  173. return *this;
  174. }
  175. ///////// LIMITS ////////
  176. Atm_Tstepper& Atm_Tstepper::setLimitPins( int limitPinLow){
  177. _limitPin[0] = limitPinLow;
  178. pinMode(_limitPin[0], INPUT);
  179. return *this;
  180. }
  181. Atm_Tstepper& Atm_Tstepper::setLimitPins( int limitPinLow, int limitPinHigh){
  182. _limitPin[0] = limitPinLow;
  183. _limitPin[1] = limitPinHigh;
  184. pinMode(_limitPin[0], INPUT);
  185. pinMode(_limitPin[1], INPUT);
  186. return *this;
  187. }
  188. Atm_Tstepper& Atm_Tstepper::setLimitType( int limitType){
  189. _limitType = limitType;
  190. return *this;
  191. }
  192. Atm_Tstepper& Atm_Tstepper::limitReversed( bool reversed){
  193. _limitReversed = reversed;
  194. return *this;
  195. }
  196. Atm_Tstepper& Atm_Tstepper::limitThresholds( int limitThreshold0,
  197. int limitThreshold1, int limitThreshold2, int limitThreshold3){
  198. _limitThresholds[0] = limitThreshold0;
  199. _limitThresholds[1] = limitThreshold1;
  200. _limitThresholds[2] = limitThreshold2;
  201. _limitThresholds[3] = limitThreshold3;
  202. return *this;
  203. }
  204. void Atm_Tstepper::updateLimitSwitch(){
  205. switch (_limitType) { // limitType!=0 means there is limit to check
  206. case NONE:
  207. return ;
  208. case DIGITAL_1:
  209. limitState[0] = digitalRead(_limitPin[0]);
  210. limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
  211. return;
  212. case DIGITAL_2:
  213. limitState[0] = digitalRead(_limitPin[0]);
  214. limitState[1] = digitalRead(_limitPin[1]);
  215. limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
  216. limitState[1] = _limitReversed ? !limitState[1] : limitState[1];
  217. return;
  218. case ANALOG_1:
  219. int read = analogRead(_limitPin[0]) ;
  220. limitState[0] = _limitThresholds[0] < read && read < _limitThresholds[1] ;
  221. limitState[1] = _limitThresholds[2] < read && read < _limitThresholds[3] ;
  222. return;
  223. }
  224. }
  225. int Atm_Tstepper::printPosition(){Serial.println(_currentStep);return 0;}
  226. Atm_Tstepper& Atm_Tstepper::onOSC( void ){
  227. // _enableReversed = reverse ;
  228. return *this;
  229. }
  230. Atm_Tstepper& Atm_Tstepper::sendOSC( void ){
  231. // _enableReversed = reverse ;
  232. return *this;
  233. }
  234. // Atm_Tstepper& Atm_Tstepper::move(long int stepRel ) {
  235. //
  236. // // _motor.move(targetStep);
  237. // // _motor.run();
  238. // // Serial.println(_motor.distanceToGo());
  239. // // _motor.setMaxSpeed(5000);
  240. // // _motor.setAcceleration(6000);
  241. // trigger( EVT_GOTO );
  242. // return *this;
  243. // }
  244. /* Nothing customizable below this line
  245. ************************************************************************************************
  246. */
  247. /* Public event methods
  248. *
  249. */
  250. Atm_Tstepper& Atm_Tstepper::homing_counter() {
  251. trigger( EVT_HOMING_COUNTER );
  252. return *this;
  253. }
  254. Atm_Tstepper& Atm_Tstepper::idle_timeout() {
  255. trigger( EVT_IDLE_TIMEOUT );
  256. return *this;
  257. }
  258. Atm_Tstepper& Atm_Tstepper::move_timeout() {
  259. trigger( EVT_MOVE_TIMEOUT );
  260. return *this;
  261. }
  262. Atm_Tstepper& Atm_Tstepper::limit_low() {
  263. trigger( EVT_LIMIT_LOW );
  264. return *this;
  265. }
  266. Atm_Tstepper& Atm_Tstepper::limit_high() {
  267. trigger( EVT_LIMIT_HIGH );
  268. return *this;
  269. }
  270. Atm_Tstepper& Atm_Tstepper::emergency() {
  271. controller->emergencyStop();
  272. trigger( EVT_EMERGENCY );
  273. return *this;
  274. }
  275. Atm_Tstepper& Atm_Tstepper::stop() {
  276. controller->stop();
  277. trigger( EVT_STOP );
  278. return *this;
  279. }
  280. Atm_Tstepper& Atm_Tstepper::ontarget() {
  281. trigger( EVT_ONTARGET );
  282. return *this;
  283. }
  284. Atm_Tstepper& Atm_Tstepper::move(long int stepRel) {
  285. _targetStep += stepRel;
  286. motor->setTargetAbs(_targetStep);
  287. controller->moveAsync(*motor);
  288. enable();
  289. trigger( EVT_MOVE );
  290. return *this;
  291. }
  292. Atm_Tstepper& Atm_Tstepper::moveTo(long int stepAbs) {
  293. _targetStep = stepAbs;
  294. motor->setTargetAbs(_targetStep);
  295. controller->moveAsync(*motor);
  296. enable();
  297. trigger( EVT_MOVE );
  298. return *this;
  299. }
  300. Atm_Tstepper& Atm_Tstepper::disable() {
  301. trigger( EVT_DISABLE );
  302. return *this;
  303. }
  304. Atm_Tstepper& Atm_Tstepper::enable() {
  305. trigger( EVT_ENABLE );
  306. return *this;
  307. }
  308. Atm_Tstepper& Atm_Tstepper::homing(int direction) {
  309. trigger( EVT_HOMING );
  310. return *this;
  311. }
  312. /*
  313. * onOnchange() push connector variants ( slots 1, autostore 0, broadcast 0 )
  314. */
  315. Atm_Tstepper& Atm_Tstepper::onOnchange( Machine& machine, int event ) {
  316. onPush( connectors, ON_ONCHANGE, 0, 1, 1, machine, event );
  317. return *this;
  318. }
  319. Atm_Tstepper& Atm_Tstepper::onOnchange( atm_cb_push_t callback, int idx ) {
  320. onPush( connectors, ON_ONCHANGE, 0, 1, 1, callback, idx );
  321. return *this;
  322. }
  323. /*
  324. * onOnchangeacceleration() push connector variants ( slots 1, autostore 0, broadcast 0 )
  325. */
  326. Atm_Tstepper& Atm_Tstepper::onOnchangeacceleration( Machine& machine, int event ) {
  327. onPush( connectors, ON_ONCHANGEACCELERATION, 0, 1, 1, machine, event );
  328. return *this;
  329. }
  330. Atm_Tstepper& Atm_Tstepper::onOnchangeacceleration( atm_cb_push_t callback, int idx ) {
  331. onPush( connectors, ON_ONCHANGEACCELERATION, 0, 1, 1, callback, idx );
  332. return *this;
  333. }
  334. /*
  335. * onOnchangeposition() push connector variants ( slots 1, autostore 0, broadcast 0 )
  336. */
  337. Atm_Tstepper& Atm_Tstepper::onOnchangeposition( Machine& machine, int event ) {
  338. onPush( connectors, ON_ONCHANGEPOSITION, 0, 1, 1, machine, event );
  339. return *this;
  340. }
  341. Atm_Tstepper& Atm_Tstepper::onOnchangeposition( atm_cb_push_t callback, int idx ) {
  342. onPush( connectors, ON_ONCHANGEPOSITION, 0, 1, 1, callback, idx );
  343. return *this;
  344. }
  345. /*
  346. * onOnchangestate() push connector variants ( slots 1, autostore 0, broadcast 0 )
  347. */
  348. Atm_Tstepper& Atm_Tstepper::onOnchangestate( Machine& machine, int event ) {
  349. onPush( connectors, ON_ONCHANGESTATE, 0, 1, 1, machine, event );
  350. return *this;
  351. }
  352. Atm_Tstepper& Atm_Tstepper::onOnchangestate( atm_cb_push_t callback, int idx ) {
  353. onPush( connectors, ON_ONCHANGESTATE, 0, 1, 1, callback, idx );
  354. return *this;
  355. }
  356. /*
  357. * onOnhighlimit() push connector variants ( slots 1, autostore 0, broadcast 0 )
  358. */
  359. Atm_Tstepper& Atm_Tstepper::onOnhighlimit( Machine& machine, int event ) {
  360. onPush( connectors, ON_ONHIGHLIMIT, 0, 1, 1, machine, event );
  361. return *this;
  362. }
  363. Atm_Tstepper& Atm_Tstepper::onOnhighlimit( atm_cb_push_t callback, int idx ) {
  364. onPush( connectors, ON_ONHIGHLIMIT, 0, 1, 1, callback, idx );
  365. return *this;
  366. }
  367. /*
  368. * onOnhomingcounterout() push connector variants ( slots 1, autostore 0, broadcast 0 )
  369. */
  370. Atm_Tstepper& Atm_Tstepper::onOnhomingcounterout( Machine& machine, int event ) {
  371. onPush( connectors, ON_ONHOMINGCOUNTEROUT, 0, 1, 1, machine, event );
  372. return *this;
  373. }
  374. Atm_Tstepper& Atm_Tstepper::onOnhomingcounterout( atm_cb_push_t callback, int idx ) {
  375. onPush( connectors, ON_ONHOMINGCOUNTEROUT, 0, 1, 1, callback, idx );
  376. return *this;
  377. }
  378. /*
  379. * onOnhomingtimeout() push connector variants ( slots 1, autostore 0, broadcast 0 )
  380. */
  381. Atm_Tstepper& Atm_Tstepper::onOnhomingtimeout( Machine& machine, int event ) {
  382. onPush( connectors, ON_ONHOMINGTIMEOUT, 0, 1, 1, machine, event );
  383. return *this;
  384. }
  385. Atm_Tstepper& Atm_Tstepper::onOnhomingtimeout( atm_cb_push_t callback, int idx ) {
  386. onPush( connectors, ON_ONHOMINGTIMEOUT, 0, 1, 1, callback, idx );
  387. return *this;
  388. }
  389. /*
  390. * onOnidletimeout() push connector variants ( slots 1, autostore 0, broadcast 0 )
  391. */
  392. Atm_Tstepper& Atm_Tstepper::onOnidletimeout( Machine& machine, int event ) {
  393. onPush( connectors, ON_ONIDLETIMEOUT, 0, 1, 1, machine, event );
  394. return *this;
  395. }
  396. Atm_Tstepper& Atm_Tstepper::onOnidletimeout( atm_cb_push_t callback, int idx ) {
  397. onPush( connectors, ON_ONIDLETIMEOUT, 0, 1, 1, callback, idx );
  398. return *this;
  399. }
  400. /*
  401. * onOnlowlimit() push connector variants ( slots 1, autostore 0, broadcast 0 )
  402. */
  403. Atm_Tstepper& Atm_Tstepper::onOnlowlimit( Machine& machine, int event ) {
  404. onPush( connectors, ON_ONLOWLIMIT, 0, 1, 1, machine, event );
  405. return *this;
  406. }
  407. Atm_Tstepper& Atm_Tstepper::onOnlowlimit( atm_cb_push_t callback, int idx ) {
  408. onPush( connectors, ON_ONLOWLIMIT, 0, 1, 1, callback, idx );
  409. return *this;
  410. }
  411. /*
  412. * onOnmovetimeout() push connector variants ( slots 1, autostore 0, broadcast 0 )
  413. */
  414. Atm_Tstepper& Atm_Tstepper::onOnmovetimeout( Machine& machine, int event ) {
  415. onPush( connectors, ON_ONMOVETIMEOUT, 0, 1, 1, machine, event );
  416. return *this;
  417. }
  418. Atm_Tstepper& Atm_Tstepper::onOnmovetimeout( atm_cb_push_t callback, int idx ) {
  419. onPush( connectors, ON_ONMOVETIMEOUT, 0, 1, 1, callback, idx );
  420. return *this;
  421. }
  422. /*
  423. * onSpeed() push connector variants ( slots 1, autostore 0, broadcast 0 )
  424. */
  425. Atm_Tstepper& Atm_Tstepper::onSpeed( Machine& machine, int event ) {
  426. onPush( connectors, ON_SPEED, 0, 1, 1, machine, event );
  427. return *this;
  428. }
  429. Atm_Tstepper& Atm_Tstepper::onSpeed( atm_cb_push_t callback, int idx ) {
  430. onPush( connectors, ON_SPEED, 0, 1, 1, callback, idx );
  431. return *this;
  432. }
  433. /* State trace method
  434. * Sets the symbol table and the default logging method for serial monitoring
  435. */
  436. Atm_Tstepper& Atm_Tstepper::trace( Stream & stream ) {
  437. Machine::setTrace( &stream, atm_serial_debug::trace,
  438. "TSTEPPER\0EVT_HOMING_COUNTER\0EVT_IDLE_TIMEOUT\0EVT_MOVE_TIMEOUT\0EVT_LIMIT_LOW\0EVT_LIMIT_HIGH\0EVT_EMERGENCY\0EVT_STOP\0EVT_ONTARGET\0EVT_MOVE\0EVT_DISABLE\0EVT_ENABLE\0ELSE\0DISABLED\0ENABLED\0RUNNING\0STOPPING\0EMERGENCY\0HOMING\0MOVE_TIMEOUT\0HOMING_COUNTEROUT" );
  439. return *this;
  440. }