Atm_Teenstep.cpp 13 KB

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