Atm_TeensyStep.cpp 7.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269
  1. #include "Atm_TeensyStep.h"
  2. /* Add optional parameters for the state machine to begin()
  3. * Add extra initialization code
  4. */
  5. Atm_TeensyStep& Atm_TeensyStep::begin(Stepper & motorRef, StepControl & stepControlRef,
  6. EthernetUDP& udpRef, OSCBundle& bndl, const char* address ) {
  7. // clang-format off
  8. const static state_t state_table[] PROGMEM = {
  9. /* ON_ENTER ON_LOOP ON_EXIT EVT_IDLE_TIMER EVT_ON_TARGET EVT_GOTO ELSE */
  10. /* IDLE */ ENT_IDLE, -1, EXT_IDLE, -1, -1, RUNNING, -1,
  11. /* READY */ ENT_READY, -1, -1, IDLE, -1, RUNNING, -1,
  12. /* RUNNING */ ENT_RUNNING, LP_RUNNING, -1, -1, STOPPING, RUNNING, -1,
  13. /* STOPPING */ ENT_STOPPING, -1, EXT_STOPPING, -1, READY, -1, -1,
  14. };
  15. // clang-format on
  16. Machine::begin( state_table, ELSE );
  17. this-> motor = &motorRef;
  18. this-> controller = &stepControlRef;
  19. _adress = address;
  20. this->_udpRef = &udpRef;
  21. this->_bndl = &bndl ;
  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_TeensyStep::event( int id ) {
  28. switch ( id ) {
  29. case EVT_IDLE_TIMER:
  30. return 0;
  31. case EVT_ON_TARGET:
  32. //motor->get(targetStep);
  33. return _currentStep == _targetStep ;
  34. // return _motor.distanceToGo()== 0 ;
  35. }
  36. return 0;
  37. }
  38. /* Add C++ code for each action
  39. * This generates the 'output' for the state machine
  40. *
  41. * Available connectors:
  42. * push( connectors, ON_ONCHANGE, 0, <v>, <up> );
  43. */
  44. void Atm_TeensyStep::action( int id ) {
  45. String strg = _adress;
  46. switch ( id ) {
  47. case ENT_IDLE:
  48. enable(0);
  49. return;
  50. case EXT_IDLE:
  51. enable(1);
  52. return;
  53. case ENT_READY:
  54. return;
  55. case ENT_RUNNING:
  56. // _controller.moveAsync(*_motor);
  57. return;
  58. case LP_RUNNING:
  59. // _motor.run();
  60. _currentStep = motor->getPosition();
  61. strg += "/step";
  62. _bndl->add(strg.c_str()).add(_currentStep);
  63. updateLimitSwitch();
  64. if(limitState[0] || limitState[1]) {emergencyStop();}
  65. // Serial.println(_motor.currentPosition());
  66. return;
  67. case ENT_STOPPING:
  68. return;
  69. case EXT_STOPPING:
  70. if(_isHoming && limitState[0]){motor->setPosition(0);}
  71. if(_isHoming && limitState[1]){maxStep = motor->getPosition();;}
  72. _isHoming=0;
  73. return;
  74. }
  75. }
  76. /* Optionally override the default trigger() method
  77. * Control how your machine processes triggers
  78. */
  79. Atm_TeensyStep& Atm_TeensyStep::trigger( int event ) {
  80. Machine::trigger( event );
  81. return *this;
  82. }
  83. Atm_TeensyStep& Atm_TeensyStep::onOSC(OSCMessage& msg ){
  84. Serial.println("OSC");
  85. int patternOffset = msg.match(_adress) ;
  86. if(patternOffset){
  87. if(msg.fullMatch("/speedAcc", patternOffset)){
  88. motor->setMaxSpeed(msg.getInt(0));
  89. motor->setAcceleration(msg.getInt(1));
  90. }
  91. if(msg.fullMatch("/enable", patternOffset)){enable(msg.getInt(0));}
  92. if(msg.fullMatch("/home", patternOffset)){home(msg.getInt(0));}
  93. if(msg.fullMatch("/move", patternOffset)){move(msg.getInt(0));}
  94. if(msg.fullMatch("/moveTo", patternOffset)){moveTo(msg.getInt(0));}
  95. if(msg.fullMatch("/stop", patternOffset)){stop();}
  96. if(msg.fullMatch("/emergencyStop", patternOffset)){emergencyStop();}
  97. return *this;
  98. }
  99. }
  100. /* Optionally override the default state() method
  101. * Control what the machine returns when another process requests its state
  102. */
  103. int Atm_TeensyStep::state( void ) {
  104. return Machine::state();
  105. }
  106. void Atm_TeensyStep::updateLimitSwitch(){
  107. switch (_limitType) { // limitType!=0 means there is limit to check
  108. case NONE:
  109. return ;
  110. case DIGITAL_1:
  111. limitState[0] = digitalRead(_limitPin[0]);
  112. limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
  113. return;
  114. case DIGITAL_2:
  115. limitState[0] = digitalRead(_limitPin[0]);
  116. limitState[1] = digitalRead(_limitPin[1]);
  117. limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
  118. limitState[1] = _limitReversed ? !limitState[1] : limitState[1];
  119. return;
  120. case ANALOG_1:
  121. int read = analogRead(_limitPin[0]) ;
  122. limitState[0] = _limitThresholds[0] < read && read < _limitThresholds[1] ;
  123. limitState[1] = _limitThresholds[2] < read && read < _limitThresholds[3] ;
  124. return;
  125. }
  126. }
  127. /* Nothing customizable below this line
  128. ************************************************************************************************
  129. */
  130. /* Public event methods
  131. *
  132. */
  133. Atm_TeensyStep& Atm_TeensyStep::setLimitPins( int limitPinLow){
  134. _limitPin[0] = limitPinLow;
  135. pinMode(_limitPin[0], INPUT);
  136. return *this;
  137. }
  138. Atm_TeensyStep& Atm_TeensyStep::setLimitPins( int limitPinLow, int limitPinHigh){
  139. _limitPin[0] = limitPinLow;
  140. _limitPin[1] = limitPinHigh;
  141. pinMode(_limitPin[0], INPUT);
  142. pinMode(_limitPin[1], INPUT);
  143. return *this;
  144. }
  145. Atm_TeensyStep& Atm_TeensyStep::setLimitType( int limitType){
  146. _limitType = limitType;
  147. return *this;
  148. }
  149. Atm_TeensyStep& Atm_TeensyStep::limitReversed( bool reversed){
  150. _limitReversed = reversed;
  151. return *this;
  152. }
  153. Atm_TeensyStep& Atm_TeensyStep::limitThresholds( int limitThreshold0,
  154. int limitThreshold1, int limitThreshold2, int limitThreshold3){
  155. _limitThresholds[0] = limitThreshold0;
  156. _limitThresholds[1] = limitThreshold1;
  157. _limitThresholds[2] = limitThreshold2;
  158. _limitThresholds[3] = limitThreshold3;
  159. return *this;
  160. }
  161. Atm_TeensyStep& Atm_TeensyStep::enable( bool enable ){
  162. enabled = enable ;
  163. enabled = _enableReversed ? !enabled : enabled ;
  164. digitalWrite(_enablePin, enabled);
  165. return *this;
  166. }
  167. Atm_TeensyStep& Atm_TeensyStep::setEnablePin( int enablePin ){
  168. _enablePin = enablePin ;
  169. pinMode(_enablePin, OUTPUT);
  170. return *this;
  171. }
  172. Atm_TeensyStep& Atm_TeensyStep::enableReversed( bool reverse ){
  173. _enableReversed = reverse ;
  174. return *this;
  175. }
  176. Atm_TeensyStep& Atm_TeensyStep::home( bool limit ){
  177. _isHoming = 1 ;
  178. limit ? move(-2147483647) : move(2147483647) ; // move to very far away until hit
  179. return *this;
  180. }
  181. Atm_TeensyStep& Atm_TeensyStep::move(long int stepRel ) {
  182. _targetStep += stepRel;
  183. motor->setTargetAbs(_targetStep);
  184. controller->moveAsync(*motor);
  185. // _motor.move(targetStep);
  186. // _motor.run();
  187. // Serial.println(_motor.distanceToGo());
  188. // _motor.setMaxSpeed(5000);
  189. // _motor.setAcceleration(6000);
  190. trigger( EVT_GOTO );
  191. return *this;
  192. }
  193. Atm_TeensyStep& Atm_TeensyStep::moveTo(long int stepAbs ) {
  194. _targetStep = stepAbs;
  195. motor->setTargetAbs(_targetStep);
  196. controller->moveAsync(*motor);
  197. trigger( EVT_GOTO );
  198. return *this;
  199. }
  200. Atm_TeensyStep& Atm_TeensyStep::stop(){
  201. controller->stopAsync();
  202. //trigger( EVT_STOPPING );
  203. return *this;
  204. }
  205. Atm_TeensyStep& Atm_TeensyStep::emergencyStop(){
  206. controller->emergencyStop();
  207. //trigger( EVT_STOPPING );
  208. return *this;
  209. }
  210. //Atm_TeensyStep& Atm_TeensyStep::onOSC(OSCMessage& msg)
  211. /*
  212. * onOnchange() push connector variants ( slots 1, autostore 0, broadcast 0 )
  213. */
  214. Atm_TeensyStep& Atm_TeensyStep::onOnchange( Machine& machine, int event ) {
  215. onPush( connectors, ON_ONCHANGE, 0, 1, 1, machine, event );
  216. return *this;
  217. }
  218. Atm_TeensyStep& Atm_TeensyStep::onOnchange( atm_cb_push_t callback, int idx ) {
  219. onPush( connectors, ON_ONCHANGE, 0, 1, 1, callback, idx );
  220. return *this;
  221. }
  222. /* State trace method
  223. * Sets the symbol table and the default logging method for serial monitoring
  224. */
  225. Atm_TeensyStep& Atm_TeensyStep::trace( Stream & stream ) {
  226. Machine::setTrace( &stream, atm_serial_debug::trace,
  227. "STEPPER\0EVT_IDLE_TIMER\0EVT_ON_TARGET\0EVT_GOTO\0ELSE\0IDLE\0READY\0RUNNING\0STOPPING" );
  228. return *this;
  229. }