Atm_Teenstep.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418
  1. #if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
  2. #ifdef TEENSYSTEP_H
  3. #include "Atm_Teenstep.h"
  4. /* Add optional parameters for the state machine to begin()
  5. * Add extra initialization code
  6. */
  7. Atm_Teenstep& Atm_Teenstep::begin(Stepper & motorRef, StepControl & stepControlRef) {
  8. // clang-format off
  9. const static state_t state_table[] PROGMEM = {
  10. /* ON_ENTER ON_LOOP ON_EXIT EVT_HOMING_LOW EVT_HOMING_HIGH EVT_MOVE_TIMEOUT EVT_LIMIT_HIGH EVT_LIMIT_LOW EVT_EMERGENCYSTOP EVT_STOP EVT_ONTARGET EVT_MOVE EVT_DISABLE EVT_ENABLE ELSE */
  11. /* DISABLED */ ENT_DISABLED, -1, -1, HOMING_LOW, HOMING_HIGH, -1, -1, -1, -1, -1, -1, -1, -1, ENABLED, -1,
  12. /* ENABLED */ ENT_ENABLED, -1, -1, HOMING_LOW, HOMING_HIGH, -1, -1, -1, -1, -1, -1, RUNNING, DISABLED, -1, -1,
  13. /* RUNNING */ ENT_RUNNING, LP_RUNNING, -1, HOMING_LOW, HOMING_HIGH, -1, -1, -1, EMERGENCY_STOP, STOPPING, ENABLED, RUNNING, -1, -1, -1,
  14. /* STOPPING */ ENT_STOPPING, -1, -1, -1, -1, -1, EMERGENCY_STOP, EMERGENCY_STOP, EMERGENCY_STOP, -1, -1, RUNNING, -1, -1, -1,
  15. /* EMERGENCY_STOP */ ENT_EMERGENCY_STOP, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, RUNNING, -1, ENABLED, -1,
  16. /* HOMING_HIGH */ ENT_HOMING_HIGH, -1, EXT_HOMING_HIGH, -1, -1, -1, ENABLED, -1, EMERGENCY_STOP, STOPPING, -1, -1, -1, -1, -1,
  17. /* HOMING_LOW */ ENT_HOMING_LOW, -1, EXT_HOMING_LOW, -1, -1, -1, -1, ENABLED, EMERGENCY_STOP, STOPPING, -1, -1, -1, -1, -1,
  18. };
  19. // clang-format on
  20. Machine::begin( state_table, ELSE );
  21. this-> motor = &motorRef;
  22. this-> controller = &stepControlRef;
  23. return *this;
  24. }
  25. /* Add C++ code for each internally handled event (input)
  26. * The code must return 1 to trigger the event
  27. */
  28. int Atm_Teenstep::event( int id ) {
  29. updateLimitSwitch();
  30. switch ( id ) {
  31. case EVT_HOMING_LOW:
  32. return 0;
  33. case EVT_HOMING_HIGH:
  34. return 0;
  35. case EVT_MOVE_TIMEOUT:
  36. return 0;
  37. case EVT_LIMIT_HIGH:
  38. return limitState[0];
  39. case EVT_LIMIT_LOW:
  40. return limitState[1];
  41. case EVT_EMERGENCYSTOP:
  42. return 0;
  43. case EVT_STOP:
  44. return 0;
  45. case EVT_ONTARGET:
  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. }
  54. return 0;
  55. }
  56. /* Add C++ code for each action
  57. * This generates the 'output' for the state machine
  58. *
  59. * Available connectors:
  60. * push( connectors, ON_CHANGE, 0, <v>, <up> );
  61. * push( connectors, ON_CHANGEPOSITION, 0, <v>, <up> );
  62. * push( connectors, ON_LIMITHIGH, 0, <v>, <up> );
  63. * push( connectors, ON_LIMITLOW, 0, <v>, <up> );
  64. */
  65. void Atm_Teenstep::action( int id ) {
  66. switch ( id ) {
  67. long int tempStep ;
  68. case ENT_DISABLED:
  69. push(connectors, ON_CHANGE, 0, state(), 0);
  70. enabled = _enableReversed ? HIGH : LOW;
  71. digitalWrite(_enablePin, enabled);
  72. sendOSC();
  73. return;
  74. case ENT_ENABLED:
  75. push(connectors, ON_CHANGE, 0, state(), 0);
  76. enabled = _enableReversed ? LOW : HIGH ;
  77. digitalWrite(_enablePin, enabled);
  78. sendOSC();
  79. return;
  80. case ENT_RUNNING:
  81. push(connectors, ON_CHANGE, 0, state(), 0);
  82. push(connectors, ON_CHANGE, 0, 2, 0);
  83. return;
  84. case LP_RUNNING:
  85. tempStep = motor->getPosition();
  86. if (tempStep != _currentStep){
  87. _currentStep = tempStep;
  88. push(connectors, ON_CHANGEPOSITION, 0, _currentStep, 0);
  89. }
  90. //updateLimitSwitch();
  91. sendOSC();
  92. return;
  93. case ENT_STOPPING:
  94. push(connectors, ON_CHANGE, 0, state(), 0);
  95. sendOSC();
  96. return;
  97. case ENT_EMERGENCY_STOP:
  98. push(connectors, ON_CHANGE, 0, state(), 0);
  99. controller->emergencyStop();
  100. trigger(EVT_ENABLE);
  101. sendOSC();
  102. return;
  103. case ENT_HOMING_HIGH:
  104. push(connectors, ON_CHANGE, 0, state(), 0);
  105. if(_limitType) {
  106. motor->setTargetRel(2147483647);
  107. controller->moveAsync(*motor);
  108. }
  109. sendOSC();
  110. return;
  111. case EXT_HOMING_HIGH:
  112. controller->emergencyStop();
  113. if(last_trigger == EVT_LIMIT_HIGH){
  114. _maxStep = motor->getPosition();
  115. push(connectors, ON_LIMITHIGH, 0, _maxStep, 0);
  116. Serial.print("Stepper maxPos ");
  117. Serial.println(motor->getPosition());
  118. trigger(EVT_ENABLE);
  119. }
  120. else{
  121. push(connectors, ON_LIMITLOW, 0, 1, 0);
  122. Serial.println("homing failed ");
  123. trigger(EVT_EMERGENCYSTOP);
  124. }
  125. return;
  126. case ENT_HOMING_LOW:
  127. push(connectors, ON_CHANGE, 0, state(), 0);
  128. if(_limitType) {
  129. motor->setTargetRel(-2147483647);
  130. controller->moveAsync(*motor);
  131. }
  132. sendOSC();
  133. return;
  134. case EXT_HOMING_LOW:
  135. controller->emergencyStop();
  136. if(last_trigger == EVT_LIMIT_LOW){
  137. push(connectors, ON_LIMITLOW, 0, 1, 0);
  138. motor->setPosition(0);
  139. Serial.print("Stepper homed ");
  140. Serial.println(motor->getPosition());
  141. trigger(EVT_ENABLE);
  142. }
  143. else{
  144. push(connectors, ON_LIMITHIGH, 0, 1, 0);
  145. Serial.println("homing failed ");
  146. trigger(EVT_EMERGENCYSTOP);
  147. }
  148. return;
  149. }
  150. }
  151. /* Optionally override the default trigger() method
  152. * Control how your machine processes triggers
  153. */
  154. Atm_Teenstep& Atm_Teenstep::trigger( int event ) {
  155. Machine::trigger( event );
  156. return *this;
  157. }
  158. /* Optionally override the default state() method
  159. * Control what the machine returns when another process requests its state
  160. */
  161. int Atm_Teenstep::state( void ) {
  162. return Machine::state();
  163. }
  164. /* CUSTOM METHODS
  165. ********************************************************************************************************
  166. */
  167. // Atm_TeensyStep& Atm_TeensyStep::enable( bool enable ){
  168. //
  169. // return *this;
  170. // }
  171. ///////// ENABLE/DISABLE ////////
  172. Atm_Teenstep& Atm_Teenstep::setEnablePin( int enablePin ){
  173. _enablePin = enablePin ;
  174. pinMode(_enablePin, OUTPUT);
  175. return *this;
  176. }
  177. Atm_Teenstep& Atm_Teenstep::enableReversed( bool reverse ){
  178. _enableReversed = reverse ;
  179. return *this;
  180. }
  181. ///////// LIMITS ////////
  182. Atm_Teenstep& Atm_Teenstep::setLimitPins( int limitPinLow){
  183. _limitPin[0] = limitPinLow;
  184. pinMode(_limitPin[0], INPUT);
  185. return *this;
  186. }
  187. Atm_Teenstep& Atm_Teenstep::setLimitPins( int limitPinLow, int limitPinHigh){
  188. _limitPin[0] = limitPinLow;
  189. _limitPin[1] = limitPinHigh;
  190. pinMode(_limitPin[0], INPUT);
  191. pinMode(_limitPin[1], INPUT);
  192. return *this;
  193. }
  194. Atm_Teenstep& Atm_Teenstep::setLimitType( int limitType){
  195. _limitType = limitType;
  196. return *this;
  197. }
  198. Atm_Teenstep& Atm_Teenstep::limitReversed( bool reversed){
  199. _limitReversed = reversed;
  200. return *this;
  201. }
  202. Atm_Teenstep& Atm_Teenstep::limitThresholds( int limitThreshold0,
  203. int limitThreshold1, int limitThreshold2, int limitThreshold3){
  204. _limitThresholds[0] = limitThreshold0;
  205. _limitThresholds[1] = limitThreshold1;
  206. _limitThresholds[2] = limitThreshold2;
  207. _limitThresholds[3] = limitThreshold3;
  208. return *this;
  209. }
  210. void Atm_Teenstep::updateLimitSwitch(){
  211. switch (_limitType) { // limitType!=0 means there is limit to check
  212. case NONE:
  213. return ;
  214. case DIGITAL_1:
  215. limitState[0] = digitalRead(_limitPin[0]);
  216. limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
  217. return;
  218. case DIGITAL_2:
  219. limitState[0] = digitalRead(_limitPin[0]);
  220. limitState[1] = digitalRead(_limitPin[1]);
  221. limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
  222. limitState[1] = _limitReversed ? !limitState[1] : limitState[1];
  223. return;
  224. case ANALOG_1:
  225. int read = analogRead(_limitPin[0]) ;
  226. limitState[0] = _limitThresholds[0] < read && read < _limitThresholds[1] ;
  227. limitState[1] = _limitThresholds[2] < read && read < _limitThresholds[3] ;
  228. return;
  229. }
  230. }
  231. Atm_Teenstep& Atm_Teenstep::onOSC( void ){
  232. // _enableReversed = reverse ;
  233. return *this;
  234. }
  235. Atm_Teenstep& Atm_Teenstep::sendOSC( void ){
  236. // _enableReversed = reverse ;
  237. return *this;
  238. }
  239. /* Nothing customizable below this line
  240. ************************************************************************************************
  241. */
  242. /* Public event methods
  243. *
  244. */
  245. Atm_Teenstep& Atm_Teenstep::homing_low() {
  246. trigger( EVT_HOMING_LOW );
  247. return *this;
  248. }
  249. Atm_Teenstep& Atm_Teenstep::homing_high() {
  250. trigger( EVT_HOMING_HIGH );
  251. return *this;
  252. }
  253. Atm_Teenstep& Atm_Teenstep::move_timeout() {
  254. trigger( EVT_MOVE_TIMEOUT );
  255. return *this;
  256. }
  257. Atm_Teenstep& Atm_Teenstep::limit_high() {
  258. trigger( EVT_LIMIT_HIGH );
  259. return *this;
  260. }
  261. Atm_Teenstep& Atm_Teenstep::limit_low() {
  262. trigger( EVT_LIMIT_LOW );
  263. return *this;
  264. }
  265. Atm_Teenstep& Atm_Teenstep::emergencystop() {
  266. trigger( EVT_EMERGENCYSTOP );
  267. return *this;
  268. }
  269. Atm_Teenstep& Atm_Teenstep::stop() {
  270. trigger( EVT_STOP );
  271. return *this;
  272. }
  273. Atm_Teenstep& Atm_Teenstep::ontarget() {
  274. trigger( EVT_ONTARGET );
  275. return *this;
  276. }
  277. Atm_Teenstep& Atm_Teenstep::move(long int stepRel) {
  278. _targetStep = _currentStep + stepRel;
  279. //Serial.println(_targetStep);
  280. motor->setTargetAbs(_targetStep);
  281. controller->moveAsync(*motor);
  282. enable();
  283. trigger( EVT_MOVE );
  284. return *this;
  285. }
  286. Atm_Teenstep& Atm_Teenstep::moveTo(long int stepAbs) {
  287. _targetStep = stepAbs;
  288. motor->setTargetAbs(_targetStep);
  289. controller->moveAsync(*motor);
  290. enable();
  291. trigger( EVT_MOVE );
  292. return *this;
  293. }
  294. Atm_Teenstep& Atm_Teenstep::disable() {
  295. trigger( EVT_DISABLE );
  296. return *this;
  297. }
  298. Atm_Teenstep& Atm_Teenstep::enable() {
  299. trigger( EVT_ENABLE );
  300. }
  301. Atm_Teenstep& Atm_Teenstep::homing(bool direction) {
  302. direction ? trigger( EVT_HOMING_HIGH ) : trigger(EVT_HOMING_LOW);
  303. return *this;
  304. }
  305. /*
  306. * onChange() push connector variants ( slots 1, autostore 0, broadcast 0 )
  307. */
  308. Atm_Teenstep& Atm_Teenstep::onChange( Machine& machine, int event ) {
  309. onPush( connectors, ON_CHANGE, 0, 1, 1, machine, event );
  310. return *this;
  311. }
  312. Atm_Teenstep& Atm_Teenstep::onChange( atm_cb_push_t callback, int idx ) {
  313. onPush( connectors, ON_CHANGE, 0, 1, 1, callback, idx );
  314. return *this;
  315. }
  316. /*
  317. * onChangeposition() push connector variants ( slots 1, autostore 0, broadcast 0 )
  318. */
  319. Atm_Teenstep& Atm_Teenstep::onChangeposition( Machine& machine, int event ) {
  320. onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, machine, event );
  321. return *this;
  322. }
  323. Atm_Teenstep& Atm_Teenstep::onChangeposition( atm_cb_push_t callback, int idx ) {
  324. onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, callback, idx );
  325. return *this;
  326. }
  327. /*
  328. * onLimithigh() push connector variants ( slots 1, autostore 0, broadcast 0 )
  329. */
  330. Atm_Teenstep& Atm_Teenstep::onLimithigh( Machine& machine, int event ) {
  331. onPush( connectors, ON_LIMITHIGH, 0, 1, 1, machine, event );
  332. return *this;
  333. }
  334. Atm_Teenstep& Atm_Teenstep::onLimithigh( atm_cb_push_t callback, int idx ) {
  335. onPush( connectors, ON_LIMITHIGH, 0, 1, 1, callback, idx );
  336. return *this;
  337. }
  338. /*
  339. * onLimitlow() push connector variants ( slots 1, autostore 0, broadcast 0 )
  340. */
  341. Atm_Teenstep& Atm_Teenstep::onLimitlow( Machine& machine, int event ) {
  342. onPush( connectors, ON_LIMITLOW, 0, 1, 1, machine, event );
  343. return *this;
  344. }
  345. Atm_Teenstep& Atm_Teenstep::onLimitlow( atm_cb_push_t callback, int idx ) {
  346. onPush( connectors, ON_LIMITLOW, 0, 1, 1, callback, idx );
  347. return *this;
  348. }
  349. /* State trace method
  350. * Sets the symbol table and the default logging method for serial monitoring
  351. */
  352. Atm_Teenstep& Atm_Teenstep::trace( Stream & stream ) {
  353. Machine::setTrace( &stream, atm_serial_debug::trace,
  354. "TEENSTEP\0EVT_HOMING_LOW\0EVT_HOMING_HIGH\0EVT_MOVE_TIMEOUT\0EVT_LIMIT_HIGH\0EVT_LIMIT_LOW\0EVT_EMERGENCYSTOP\0EVT_STOP\0EVT_ONTARGET\0EVT_MOVE\0EVT_DISABLE\0EVT_ENABLE\0ELSE\0DISABLED\0ENABLED\0RUNNING\0STOPPING\0EMERGENCY_STOP\0HOMING_HIGH\0HOMING_LOW" );
  355. return *this;
  356. }
  357. #endif
  358. #endif