Atm_Teenstep.cpp 13 KB

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