Atm_Teenstep.cpp 12 KB

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