Просмотр исходного кода

Initial commit

import existing objects from Hadrien Tequi development
titi 5 лет назад
Сommit
58376676fe
6 измененных файлов с 963 добавлено и 0 удалено
  1. 412 0
      Atm_Teenstep.cpp
  2. 157 0
      Atm_Teenstep.h
  3. 36 0
      Atm_Teenstep_OSC.cpp
  4. 31 0
      Atm_Teenstep_OSC.h
  5. 260 0
      Atm_out.cpp
  6. 67 0
      Atm_out.h

+ 412 - 0
Atm_Teenstep.cpp

@@ -0,0 +1,412 @@
+#include "Atm_Teenstep.h"
+
+/* Add optional parameters for the state machine to begin()
+ * Add extra initialization code
+ */
+
+Atm_Teenstep& Atm_Teenstep::begin(Stepper & motorRef, StepControl & stepControlRef) {
+  // clang-format off
+  const static state_t state_table[] PROGMEM = {
+    /*                             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 */
+    /*       DISABLED */       ENT_DISABLED,         -1,              -1,     HOMING_LOW,     HOMING_HIGH,               -1,             -1,             -1,                -1,       -1,           -1,       -1,          -1,    ENABLED,   -1,
+    /*        ENABLED */        ENT_ENABLED,         -1,              -1,     HOMING_LOW,     HOMING_HIGH,               -1,             -1,             -1,                -1,       -1,           -1,  RUNNING,    DISABLED,         -1,   -1,
+    /*        RUNNING */        ENT_RUNNING, LP_RUNNING,              -1,     HOMING_LOW,     HOMING_HIGH,               -1,             -1,             -1,    EMERGENCY_STOP, STOPPING,      ENABLED,  RUNNING,          -1,         -1,   -1,
+    /*       STOPPING */       ENT_STOPPING,         -1,              -1,             -1,              -1,               -1, EMERGENCY_STOP, EMERGENCY_STOP,    EMERGENCY_STOP,       -1,           -1,  RUNNING,          -1,         -1,   -1,
+    /* EMERGENCY_STOP */ ENT_EMERGENCY_STOP,         -1,              -1,             -1,              -1,               -1,             -1,             -1,                -1,       -1,           -1,  RUNNING,          -1,    ENABLED,   -1,
+    /*    HOMING_HIGH */    ENT_HOMING_HIGH,         -1, EXT_HOMING_HIGH,             -1,              -1,               -1,        ENABLED,             -1,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
+    /*     HOMING_LOW */     ENT_HOMING_LOW,         -1,  EXT_HOMING_LOW,             -1,              -1,               -1,            -1,        ENABLED,    EMERGENCY_STOP, STOPPING,           -1,       -1,          -1,         -1,   -1,
+  };
+  // clang-format on
+  Machine::begin( state_table, ELSE );
+  this-> motor =   &motorRef;
+  this-> controller = &stepControlRef;
+  return *this;
+}
+
+/* Add C++ code for each internally handled event (input)
+ * The code must return 1 to trigger the event
+ */
+
+int Atm_Teenstep::event( int id ) {
+  updateLimitSwitch();
+  switch ( id ) {
+    case EVT_HOMING_LOW:
+      return 0;
+    case EVT_HOMING_HIGH:
+      return 0;
+    case EVT_MOVE_TIMEOUT:
+      return 0;
+    case EVT_LIMIT_HIGH:
+      return limitState[0];
+    case EVT_LIMIT_LOW:
+      return limitState[1];
+    case EVT_EMERGENCYSTOP:
+      return 0;
+    case EVT_STOP:
+      return 0;
+    case EVT_ONTARGET:
+      return _currentStep == _targetStep;
+    case EVT_MOVE:
+      return 0;
+    case EVT_DISABLE:
+      return 0;
+    case EVT_ENABLE:
+      return 0;
+  }
+  return 0;
+}
+
+/* Add C++ code for each action
+ * This generates the 'output' for the state machine
+ *
+ * Available connectors:
+ *   push( connectors, ON_CHANGE, 0, <v>, <up> );
+ *   push( connectors, ON_CHANGEPOSITION, 0, <v>, <up> );
+ *   push( connectors, ON_LIMITHIGH, 0, <v>, <up> );
+ *   push( connectors, ON_LIMITLOW, 0, <v>, <up> );
+ */
+
+void Atm_Teenstep::action( int id ) {
+  switch ( id ) {
+    long int tempStep ;
+    case ENT_DISABLED:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      enabled = _enableReversed ? HIGH : LOW;
+      digitalWrite(_enablePin, enabled);
+      sendOSC();
+      return;
+    case ENT_ENABLED:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      enabled = _enableReversed ? LOW : HIGH ;
+      digitalWrite(_enablePin, enabled);
+      sendOSC();
+      return;
+    case ENT_RUNNING:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      push(connectors, ON_CHANGE, 0,  2, 0);
+      return;
+    case LP_RUNNING:
+      tempStep = motor->getPosition();
+      if (tempStep != _currentStep){
+        _currentStep =  tempStep;
+        push(connectors, ON_CHANGEPOSITION, 0,  _currentStep, 0);
+      }
+
+      //updateLimitSwitch();
+      sendOSC();
+      return;
+    case ENT_STOPPING:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      sendOSC();
+      return;
+    case ENT_EMERGENCY_STOP:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      controller->emergencyStop();
+      trigger(EVT_ENABLE);
+      sendOSC();
+      return;
+    case ENT_HOMING_HIGH:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      if(_limitType) {
+        motor->setTargetRel(2147483647);
+        controller->moveAsync(*motor);
+        }
+      sendOSC();
+      return;
+    case EXT_HOMING_HIGH:
+      controller->emergencyStop();
+      if(last_trigger == EVT_LIMIT_HIGH){
+        _maxStep = motor->getPosition();
+        push(connectors, ON_LIMITHIGH, 0,  _maxStep, 0);
+        Serial.print("Stepper maxPos ");
+        Serial.println(motor->getPosition());
+        trigger(EVT_ENABLE);
+      }
+      else{
+        push(connectors, ON_LIMITLOW, 0,  1, 0);
+        Serial.println("homing failed ");
+        trigger(EVT_EMERGENCYSTOP);
+      }
+
+      return;
+    case ENT_HOMING_LOW:
+      push(connectors, ON_CHANGE, 0,  state(), 0);
+      if(_limitType) {
+        motor->setTargetRel(-2147483647);
+        controller->moveAsync(*motor);
+        }
+      sendOSC();
+      return;
+    case EXT_HOMING_LOW:
+      controller->emergencyStop();
+      if(last_trigger == EVT_LIMIT_LOW){
+        push(connectors, ON_LIMITLOW, 0,  1, 0);
+        motor->setPosition(0);
+        Serial.print("Stepper homed ");
+        Serial.println(motor->getPosition());
+        trigger(EVT_ENABLE);
+      }
+      else{
+        push(connectors, ON_LIMITHIGH, 0,  1, 0);
+        Serial.println("homing failed ");
+        trigger(EVT_EMERGENCYSTOP);
+      }
+
+
+      return;
+  }
+}
+
+/* Optionally override the default trigger() method
+ * Control how your machine processes triggers
+ */
+
+Atm_Teenstep& Atm_Teenstep::trigger( int event ) {
+  Machine::trigger( event );
+  return *this;
+}
+
+/* Optionally override the default state() method
+ * Control what the machine returns when another process requests its state
+ */
+
+int Atm_Teenstep::state( void ) {
+  return Machine::state();
+}
+
+/* CUSTOM METHODS
+********************************************************************************************************
+*/
+
+// Atm_TeensyStep& Atm_TeensyStep::enable( bool enable ){
+//
+//   return *this;
+// }
+
+/////////   ENABLE/DISABLE    ////////
+
+Atm_Teenstep& Atm_Teenstep::setEnablePin( int enablePin ){
+  _enablePin = enablePin ;
+  pinMode(_enablePin, OUTPUT);
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::enableReversed( bool reverse ){
+  _enableReversed = reverse ;
+  return *this;
+}
+
+/////////   LIMITS    ////////
+
+Atm_Teenstep& Atm_Teenstep::setLimitPins( int limitPinLow){
+  _limitPin[0] = limitPinLow;
+  pinMode(_limitPin[0], INPUT);
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::setLimitPins( int limitPinLow, int limitPinHigh){
+ _limitPin[0] = limitPinLow;
+ _limitPin[1] = limitPinHigh;
+ pinMode(_limitPin[0], INPUT);
+ pinMode(_limitPin[1], INPUT);
+ return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::setLimitType( int limitType){
+ _limitType = limitType;
+ return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limitReversed( bool reversed){
+ _limitReversed = reversed;
+ return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limitThresholds( int limitThreshold0,
+       int limitThreshold1,  int limitThreshold2, int limitThreshold3){
+ _limitThresholds[0] = limitThreshold0;
+ _limitThresholds[1] = limitThreshold1;
+ _limitThresholds[2] = limitThreshold2;
+ _limitThresholds[3] = limitThreshold3;
+ return *this;
+}
+
+void Atm_Teenstep::updateLimitSwitch(){
+  switch (_limitType) { // limitType!=0 means there is limit to check
+    case NONE:
+      return ;
+    case DIGITAL_1:
+      limitState[0] = digitalRead(_limitPin[0]);
+      limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
+      return;
+    case DIGITAL_2:
+    limitState[0] = digitalRead(_limitPin[0]);
+    limitState[1] = digitalRead(_limitPin[1]);
+    limitState[0] = _limitReversed ? !limitState[0] : limitState[0];
+    limitState[1] = _limitReversed ? !limitState[1] : limitState[1];
+      return;
+    case ANALOG_1:
+    int read = analogRead(_limitPin[0]) ;
+    limitState[0] = _limitThresholds[0] < read && read < _limitThresholds[1] ;
+    limitState[1] = _limitThresholds[2] < read && read < _limitThresholds[3] ;
+      return;
+  }
+
+}
+
+
+Atm_Teenstep& Atm_Teenstep::onOSC( void ){
+//  _enableReversed = reverse ;
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::sendOSC( void ){
+//  _enableReversed = reverse ;
+  return *this;
+}
+
+/* Nothing customizable below this line
+ ************************************************************************************************
+*/
+
+/* Public event methods
+ *
+ */
+ Atm_Teenstep& Atm_Teenstep::homing_low() {
+   trigger( EVT_HOMING_LOW );
+   return *this;
+ }
+
+ Atm_Teenstep& Atm_Teenstep::homing_high() {
+   trigger( EVT_HOMING_HIGH );
+   return *this;
+ }
+
+Atm_Teenstep& Atm_Teenstep::move_timeout() {
+  trigger( EVT_MOVE_TIMEOUT );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limit_high() {
+  trigger( EVT_LIMIT_HIGH );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::limit_low() {
+  trigger( EVT_LIMIT_LOW );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::emergencystop() {
+  trigger( EVT_EMERGENCYSTOP );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::stop() {
+  trigger( EVT_STOP );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::ontarget() {
+  trigger( EVT_ONTARGET );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::move(long int stepRel) {
+  _targetStep   = _currentStep + stepRel;
+  //Serial.println(_targetStep);
+  motor->setTargetAbs(_targetStep);
+  controller->moveAsync(*motor);
+  enable();
+  trigger( EVT_MOVE );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::moveTo(long int stepAbs) {
+  _targetStep   = stepAbs;
+  motor->setTargetAbs(_targetStep);
+  controller->moveAsync(*motor);
+  enable();
+  trigger( EVT_MOVE );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::disable() {
+  trigger( EVT_DISABLE );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::enable() {
+  trigger( EVT_ENABLE );
+}
+
+Atm_Teenstep& Atm_Teenstep::homing(bool direction) {
+  direction ? trigger( EVT_HOMING_HIGH ) : trigger(EVT_HOMING_LOW);
+  return *this;
+}
+
+/*
+ * onChange() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onChange( Machine& machine, int event ) {
+  onPush( connectors, ON_CHANGE, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onChange( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_CHANGE, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/*
+ * onChangeposition() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onChangeposition( Machine& machine, int event ) {
+  onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onChangeposition( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_CHANGEPOSITION, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/*
+ * onLimithigh() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onLimithigh( Machine& machine, int event ) {
+  onPush( connectors, ON_LIMITHIGH, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onLimithigh( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_LIMITHIGH, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/*
+ * onLimitlow() push connector variants ( slots 1, autostore 0, broadcast 0 )
+ */
+
+Atm_Teenstep& Atm_Teenstep::onLimitlow( Machine& machine, int event ) {
+  onPush( connectors, ON_LIMITLOW, 0, 1, 1, machine, event );
+  return *this;
+}
+
+Atm_Teenstep& Atm_Teenstep::onLimitlow( atm_cb_push_t callback, int idx ) {
+  onPush( connectors, ON_LIMITLOW, 0, 1, 1, callback, idx );
+  return *this;
+}
+
+/* State trace method
+ * Sets the symbol table and the default logging method for serial monitoring
+ */
+
+ Atm_Teenstep& Atm_Teenstep::trace( Stream & stream ) {
+   Machine::setTrace( &stream, atm_serial_debug::trace,
+     "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" );
+   return *this;
+ }

+ 157 - 0
Atm_Teenstep.h

@@ -0,0 +1,157 @@
+#pragma once
+
+#include <Automaton.h>
+#include <TeensyStep.h>
+
+class Atm_Teenstep: public Machine {
+
+ public:
+   enum { DISABLED, ENABLED, RUNNING, STOPPING, EMERGENCY_STOP, HOMING_HIGH, HOMING_LOW }; // STATES
+   enum { 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 }; // EVENTS
+  Atm_Teenstep( void ) : Machine() {};
+  Atm_Teenstep& begin( Stepper & motorRef, StepControl & stepControlRef );
+  Atm_Teenstep& trace( Stream & stream );
+  Atm_Teenstep& trigger( int event );
+  int state( void );
+  Atm_Teenstep& onChange( Machine& machine, int event = 0 );
+  Atm_Teenstep& onChange( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& onChangeposition( Machine& machine, int event = 0 );
+  Atm_Teenstep& onChangeposition( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& onLimithigh( Machine& machine, int event = 0 );
+  Atm_Teenstep& onLimithigh( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& onLimitlow( Machine& machine, int event = 0 );
+  Atm_Teenstep& onLimitlow( atm_cb_push_t callback, int idx = 0 );
+  Atm_Teenstep& homing_low( void );
+  Atm_Teenstep& homing_high( void );
+  Atm_Teenstep& move_timeout( void );
+  Atm_Teenstep& limit_high( void );
+  Atm_Teenstep& limit_low( void );
+  Atm_Teenstep& emergencystop( void );
+  Atm_Teenstep& stop( void );
+  Atm_Teenstep& ontarget( void );
+  Atm_Teenstep& move( void );
+  Atm_Teenstep& disable( void );
+  Atm_Teenstep& enable( void );
+
+
+  Atm_Teenstep& move( long int stepRel );
+  Atm_Teenstep& moveTo( long int stepAbs );
+  Atm_Teenstep& homing( bool direction );
+
+  Atm_Teenstep& setLimitType( int limitType = 0);
+  Atm_Teenstep& setLimitPins( int limitPinLow);
+  Atm_Teenstep& setLimitPins( int limitPinLow, int limitPinHigh);
+  Atm_Teenstep& limitReversed( bool reversed );
+  Atm_Teenstep& limitThresholds( int limitThreshold0, int limitThreshold1,
+                                  int limitThreshold2, int limitThreshold3);
+  bool limitState[2] ; // up to two limits, at least one for homing
+
+  virtual Atm_Teenstep& onOSC( void );
+  virtual Atm_Teenstep& sendOSC( void );
+
+  Stepper * motor;
+  StepControl * controller;
+
+  Atm_Teenstep& setEnablePin( int enablePin );
+  Atm_Teenstep& enableReversed( bool reverse );
+  bool enabled ;
+
+
+
+ private:
+  enum { ENT_DISABLED, ENT_ENABLED, ENT_RUNNING, LP_RUNNING, ENT_STOPPING, ENT_EMERGENCY_STOP, ENT_HOMING_HIGH, EXT_HOMING_HIGH, ENT_HOMING_LOW, EXT_HOMING_LOW }; // ACTIONS
+  enum { ON_CHANGE, ON_CHANGEPOSITION, ON_LIMITHIGH, ON_LIMITLOW, CONN_MAX }; // CONNECTORS
+  atm_connector connectors[CONN_MAX];
+  int event( int id );
+  void action( int id );
+
+  atm_timer_millis idle_timer ;
+  int IDLE_TIMEOUT_DURATION = 500000 ;
+  atm_timer_millis moving_timer ;
+  int MOVING_TIMEOUT_DURATION = 12000000 ;
+  atm_counter homing_counterout ;
+
+  long int _currentStep = 0;
+  long int _targetStep = 0;
+  long int _maxStep ;
+
+  int _enablePin = -1;
+  bool _enableReversed = 0 ;
+
+  int _limitPin[2];
+  enum { NONE, DIGITAL_1, DIGITAL_2, ANALOG_1 };
+  int _limitType; //type of limit switch, from list over
+  bool _limitReversed ; //invert logic of limit switches
+  int _limitThresholds[4] ; //analog value  range for two analog limits
+  void updateLimitSwitch();
+};
+
+/*
+Automaton::ATML::begin - Automaton Markup Language
+
+<?xml version="1.0" encoding="UTF-8"?>
+<machines>
+  <machine name="Atm_Teenstep">
+    <states>
+      <DISABLED index="0" on_enter="ENT_DISABLED">
+        <EVT_ENABLE>ENABLED</EVT_ENABLE>
+      </DISABLED>
+      <ENABLED index="1" on_enter="ENT_ENABLED">
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+        <EVT_DISABLE>DISABLED</EVT_DISABLE>
+      </ENABLED>
+      <RUNNING index="2" on_enter="ENT_RUNNING" on_loop="LP_RUNNING">
+        <EVT_LIMIT_HIGH>EMERGENCY_STOP</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>EMERGENCY_STOP</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_STOP>STOPPING</EVT_STOP>
+        <EVT_ONTARGET>ENABLED</EVT_ONTARGET>
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+      </RUNNING>
+      <STOPPING index="3" on_enter="ENT_STOPPING">
+        <EVT_LIMIT_HIGH>EMERGENCY_STOP</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>EMERGENCY_STOP</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+      </STOPPING>
+      <EMERGENCY_STOP index="4" on_enter="ENT_EMERGENCY_STOP">
+        <EVT_MOVE>RUNNING</EVT_MOVE>
+        <EVT_ENABLE>ENABLED</EVT_ENABLE>
+      </EMERGENCY_STOP>
+      <HOMING_HIGH index="5" on_enter="ENT_HOMING_HIGH" on_exit="EXT_HOMING_HIGH">
+        <EVT_LIMIT_HIGH>ENABLED</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>EMERGENCY_STOP</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_STOP>STOPPING</EVT_STOP>
+      </HOMING_HIGH>
+      <HOMING_LOW index="6" on_enter="ENT_HOMING_LOW" on_exit="EXT_HOMING_LOW">
+        <EVT_LIMIT_HIGH>EMERGENCY_STOP</EVT_LIMIT_HIGH>
+        <EVT_LIMIT_LOW>ENABLED</EVT_LIMIT_LOW>
+        <EVT_EMERGENCYSTOP>EMERGENCY_STOP</EVT_EMERGENCYSTOP>
+        <EVT_STOP>STOPPING</EVT_STOP>
+      </HOMING_LOW>
+    </states>
+    <events>
+      <EVT_MOVE_TIMEOUT index="0" access="MIXED"/>
+      <EVT_LIMIT_HIGH index="1" access="MIXED"/>
+      <EVT_LIMIT_LOW index="2" access="MIXED"/>
+      <EVT_EMERGENCYSTOP index="3" access="MIXED"/>
+      <EVT_STOP index="4" access="MIXED"/>
+      <EVT_ONTARGET index="5" access="MIXED"/>
+      <EVT_MOVE index="6" access="MIXED"/>
+      <EVT_DISABLE index="7" access="MIXED"/>
+      <EVT_ENABLE index="8" access="MIXED"/>
+    </events>
+    <connectors>
+      <CHANGE autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+      <CHANGEPOSITION autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+      <LIMITHIGH autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+      <LIMITLOW autostore="0" broadcast="0" dir="PUSH" slots="1"/>
+    </connectors>
+    <methods>
+    </methods>
+  </machine>
+</machines>
+
+Automaton::ATML::end
+*/

+ 36 - 0
Atm_Teenstep_OSC.cpp

@@ -0,0 +1,36 @@
+#include "Atm_Teenstep_OSC.h"
+
+Atm_Teenstep_OSC& Atm_Teenstep_OSC::begin(Atm_Teenstep& stepperMachineRef, EthernetUDP& udpRef, OSCBundle& bndl, const char* address) {
+  this-> stepperMachine = &stepperMachineRef;
+  _adress = address;
+  this->_udpRef =   &udpRef;
+  this->_bndl = &bndl ;
+  //stepperMachine->onChangeposition( sendPosition, 0);
+  return *this;
+}
+
+
+
+Atm_Teenstep_OSC& Atm_Teenstep_OSC::onOSC(OSCMessage& msg ){
+  Serial.println("OSC");
+  int patternOffset = msg.match(_adress) ;
+  if(patternOffset){
+    if(msg.fullMatch("/speedAcc", patternOffset)){
+      stepperMachine->motor->setMaxSpeed(msg.getInt(0));
+      stepperMachine->motor->setAcceleration(msg.getInt(1));
+    }
+    if(msg.fullMatch("/enable", patternOffset)){msg.getInt(0) ? stepperMachine->trigger(stepperMachine->EVT_ENABLE) : stepperMachine->trigger(stepperMachine->EVT_DISABLE);}
+    //if(msg.fullMatch("/home", patternOffset)){home(msg.getInt(0));}
+    if(msg.fullMatch("/move", patternOffset)){stepperMachine->move(msg.getInt(0));Serial.println(msg.getInt(0));}
+    if(msg.fullMatch("/moveTo", patternOffset)){stepperMachine->moveTo(msg.getInt(0));}
+    if(msg.fullMatch("/stop", patternOffset)){stepperMachine->stop();}
+    if(msg.fullMatch("/emergencyStop", patternOffset)){stepperMachine->emergencystop();}
+    if(msg.fullMatch("/home", patternOffset)){stepperMachine->homing(msg.getInt(0));}
+
+    return *this;
+  }
+}
+
+void Atm_Teenstep_OSC::sendPosition(int idx, int v, int up) {
+  _bndl->add(_adress).add(v);
+}

+ 31 - 0
Atm_Teenstep_OSC.h

@@ -0,0 +1,31 @@
+#pragma once
+
+#include "Atm_Teenstep.h"
+
+#include <EthernetUdp.h>
+#include <OSCMessage.h>
+#include <OSCBundle.h>
+
+class Atm_Teenstep_OSC {
+
+  public:
+    Atm_Teenstep_OSC( void ){};
+    Atm_Teenstep_OSC& begin(Atm_Teenstep & stepperMachineRef,
+                              EthernetUDP& udpRef,
+                               OSCBundle& bndl,
+                               const char* address);
+    Atm_Teenstep* stepperMachine ;
+    const char* _adress = "/OSC";
+    EthernetUDP* _udpRef ;
+    Atm_Teenstep_OSC& onOSC(OSCMessage& msg );
+    Atm_Teenstep_OSC& sendOSC( void );
+
+    void sendPosition(int idx, int v, int up);
+
+  private:
+   // AccelStepper _motor;
+   // Stepper *_motor;       // STEP pin: 2, DIR pin: 3
+   // StepControl _controller;
+   OSCBundle* _bndl;
+
+};

+ 260 - 0
Atm_out.cpp

@@ -0,0 +1,260 @@
+#include "Atm_out.h"
+
+Atm_out& Atm_out::begin( int attached_pin, bool activeLow,
+            EthernetUDP& udpRef, OSCBundle& bndl, const char* address ) {
+  // clang-format off
+  static const state_t state_table[] PROGMEM = {
+    /*               ON_ENTER    ON_LOOP    ON_EXIT  EVT_ON_TIMER  EVT_OFF_TIMER EVT_WT_TIMER EVT_COUNTER  EVT_ON  EVT_OFF  EVT_BLINK  EVT_TOGGLE  EVT_TOGGLE_BLINK   ELSE */
+    /* IDLE      */  ENT_INIT, ATM_SLEEP,        -1,           -1,            -1,          -1,         -1,  WT_ON,      -1,  WT_START,         ON,         WT_START,    -1, // LED off
+    /* ON        */    ENT_ON, ATM_SLEEP,        -1,           -1,            -1,          -1,         -1,     -1,     OFF,  WT_START,        OFF,              OFF,    -1, // LED on
+    /* START     */    ENT_ON,        -1,        -1,    BLINK_OFF,            -1,          -1,         -1,  WT_ON,     OFF,        -1,        OFF,              OFF,    -1, // Start blinking
+    /* BLINK_OFF */   ENT_OFF,        -1,        -1,           -1,          LOOP,          -1,         -1,  WT_ON,     OFF,        -1,        OFF,              OFF,    -1,
+    /* LOOP      */        -1,        -1,        -1,           -1,            -1,          -1,       DONE,  WT_ON,     OFF,        -1,        OFF,              OFF, START,
+    /* DONE      */        -1,        -1, EXT_CHAIN,           -1,           OFF,          -1,         -1,  WT_ON,     OFF,  WT_START,        OFF,              OFF,    -1, // Wait after last blink
+    /* OFF       */   ENT_OFF,        -1,        -1,           -1,            -1,          -1,         -1,  WT_ON,     OFF,  WT_START,         -1,               -1,  IDLE, // All off -> IDLE
+    /* WT_ON     */        -1,        -1,        -1,           -1,            -1,          ON,         -1,  WT_ON,     OFF,  WT_START,         -1,               -1,    -1, // LEAD for ON
+    /* WT_START  */        -1,        -1,        -1,           -1,            -1,       START,         -1,  WT_ON,     OFF,  WT_START,         -1,               -1,    -1, // LEAD for BLINK
+  };
+  // clang-format on
+  Machine::begin( state_table, ELSE );
+  pin = attached_pin;
+  this->activeLow = activeLow;
+  level = 255;
+  toLow = 0;
+  toHigh = 255;
+  wrap = false;
+  pinMode( pin, OUTPUT );
+  digitalWrite( pin, activeLow ? HIGH : LOW );
+  on_timer.set( 500 );
+  off_timer.set( 500 );
+  pwm( 512, 1 );
+  lead_timer.set( 0 );
+  repeat_count = ATM_COUNTER_OFF;
+  counter.set( repeat_count );
+  while ( state() != 0 ) cycle();
+  _adress = address;
+  this->_udpRef =   &udpRef;
+  this->_bndl = &bndl ;
+  return *this;
+}
+
+Atm_out& Atm_out::pwm( uint16_t width, float freq ) {
+
+    if ( freq > -1 ) {
+		this->freq = freq;
+	} else {
+		freq = this->freq;
+	}
+	this->width = width;
+	float cycle_width = 1000 / freq;
+	on_timer.set( cycle_width / 1024 * this->width );
+	off_timer.set( cycle_width / 1024 * ( 1024 - this->width ) );
+	return *this;
+}
+
+Atm_out& Atm_out::frequency( float freq ) {
+
+	this->freq = freq;
+	float cycle_width = 1000 / freq;
+	on_timer.set( cycle_width / 1024 * this->width );
+	off_timer.set( cycle_width / 1024 * ( 1024 - this->width ) );
+	return *this;
+}
+
+int Atm_out::event( int id ) {
+  switch ( id ) {
+    case EVT_ON_TIMER:
+      return on_timer.expired( this );
+    case EVT_OFF_TIMER:
+      return off_timer.expired( this );
+    case EVT_WT_TIMER:
+      return lead_timer.expired( this );
+    case EVT_COUNTER:
+      return counter.expired();
+  }
+  return 0;
+}
+
+void Atm_out::action( int id ) {
+  switch ( id ) {
+    case ENT_INIT:
+      counter.set( repeat_count );
+      return;
+    case ENT_ON:
+      if ( on_timer.value > 0 ) { // Never turn if on_timer is zero (duty cycle 0 must be dark)
+        if ( activeLow ) {
+          digitalWrite( pin, LOW );
+        } else {
+          if ( level == toHigh ) {
+            digitalWrite( pin, HIGH );
+          } else {
+            analogWrite( pin, mapLevel( level ) );
+          }
+        }
+      }
+      return;
+    case ENT_OFF:
+      counter.decrement();
+      if ( !activeLow ) {
+        digitalWrite( pin, LOW );
+      } else {
+        if ( level == toHigh ) {
+          digitalWrite( pin, HIGH );
+        } else {
+          analogWrite( pin, mapLevel( level ) );
+        }
+      }
+      return;
+    case EXT_CHAIN:
+      onfinish.push( 0 );
+      return;
+  }
+}
+
+int Atm_out::mapLevel( int level ) {
+  if ( levelMapSize ) {
+    return levelMap[level];
+  } else {
+    return map( level, toLow, toHigh, 0, 255 );
+  }
+}
+
+Atm_out& Atm_out::on( void ) {
+  trigger( EVT_ON );
+  return *this;
+}
+
+Atm_out& Atm_out::off( void ) {
+  trigger( EVT_OFF );
+  return *this;
+}
+
+Atm_out& Atm_out::toggle( void ) {
+  trigger( EVT_TOGGLE );
+  return *this;
+}
+
+Atm_out& Atm_out::toggleBlink( void ) {
+  trigger( EVT_TOGGLE_BLINK );
+  return *this;
+}
+
+Atm_out& Atm_out::start( void ) {
+  trigger( EVT_BLINK );
+  return *this;
+}
+
+Atm_out& Atm_out::onFinish( Machine& machine, int event /* = 0 */ ) {
+  onfinish.set( &machine, event );
+  return *this;
+}
+
+Atm_out& Atm_out::onFinish( atm_cb_push_t callback, int idx /* = 0 */ ) {
+  onfinish.set( callback, idx );
+  return *this;
+}
+
+Atm_out& Atm_out::blink( uint32_t duration, uint32_t pause_duration, uint16_t repeat_count /* = ATM_COUNTER_OFF */ ) {
+  blink( duration );  // Time in which led is fully on
+  pause( pause_duration );
+  repeat( repeat_count );
+  return *this;
+}
+
+Atm_out& Atm_out::blink( uint32_t duration ) {
+  on_timer.set( duration );  // Time in which led is fully on
+  return *this;
+}
+
+Atm_out& Atm_out::blink( void ) {
+  trigger( EVT_BLINK );
+  return *this;
+}
+
+Atm_out& Atm_out::range( int toLow, int toHigh, bool wrap /* = false */ ) {
+  this->toLow = toLow;
+  this->toHigh = toHigh;
+  this->wrap = wrap;
+  level = toHigh;
+  return *this;
+}
+
+Atm_out& Atm_out::levels( unsigned char* map, int mapsize, bool wrap /* = false */ ) {
+  this->levelMap = map;
+  levelMapSize = mapsize;
+  range( 0, mapsize - 1, wrap );
+  return *this;
+}
+
+Atm_out& Atm_out::pause( uint32_t duration ) {  // Time in which led is fully off
+  off_timer.set( duration ? duration : 1 );     // Make sure off_timer is never 0 (work around)
+  return *this;
+}
+
+Atm_out& Atm_out::fade( int fade ) {
+  return *this;
+}  // Dummy for method compatibility with Atm_fade
+
+Atm_out& Atm_out::lead( uint32_t ms ) {
+  lead_timer.set( ms );
+  return *this;
+}
+
+Atm_out& Atm_out::repeat( uint16_t repeat ) {
+  counter.set( repeat_count = repeat );
+  return *this;
+}
+
+int Atm_out::brightness( int level /* = -1 */ ) {
+  if ( level > -1 ) {
+    this->level = level;
+    if ( current == ON || current == START ) {
+      analogWrite( pin, mapLevel( level ) );
+    }
+  }
+  return this->level;
+}
+
+int Atm_out::brighten( int v ) {
+  if ( abs( v ) == 1 ) {
+    int br = (int)this->level + v;
+    if ( br > toHigh )
+      br = wrap ? toLow : toHigh;
+    if ( br < toLow )
+      br = wrap ? toHigh : toLow;
+    brightness( br );
+  }
+  return this->level;
+}
+
+Atm_out& Atm_out::trigger( int event ) {
+  if ( event > ELSE ) {
+    brighten( event == EVT_BRUP ? 1 : -1 );
+  } else {
+    Machine::trigger( event );
+  }
+  return *this;
+}
+
+Atm_out& Atm_out::onOSC(OSCMessage& msg ){
+  Serial.println("OSC");
+  int patternOffset = msg.match(_adress) ;
+  if(patternOffset){
+
+    if(msg.fullMatch("/on", patternOffset)){trigger(EVT_ON);}
+    if(msg.fullMatch("/off", patternOffset)){trigger(EVT_OFF);}
+    if(msg.fullMatch("/toggle", patternOffset)){trigger(EVT_TOGGLE);}
+    if(msg.fullMatch("/blink", patternOffset)){trigger(EVT_BLINK);}
+    if(msg.fullMatch("/brightness", patternOffset)){brightness(msg.getInt(0));}
+
+    return *this;
+  }
+}
+
+Atm_out& Atm_out::trace( Stream& stream ) {
+  setTrace( &stream, atm_serial_debug::trace,
+            "LED\0EVT_ON_TIMER\0EVT_OFF_TIMER\0EVT_WT_TIMER\0EVT_COUNTER\0EVT_ON\0EVT_OFF\0EVT_"
+            "BLINK\0EVT_TOGGLE\0EVT_TOGGLE_BLINK\0ELSE\0"
+            "IDLE\0ON\0START\0BLINK_OFF\0LOOP\0DONE\0OFF\0WT_ON\0WT_START" );
+  return *this;
+}

+ 67 - 0
Atm_out.h

@@ -0,0 +1,67 @@
+#pragma once
+
+#include <Automaton.h>
+
+#include <EthernetUdp.h>
+#include <OSCMessage.h>
+#include <OSCBundle.h>
+
+class Atm_out : public Machine {
+ public:
+  enum { IDLE, ON, START, BLINK_OFF, LOOP, DONE, OFF, WT_ON, WT_START };
+  enum { EVT_ON_TIMER, EVT_OFF_TIMER, EVT_WT_TIMER, EVT_COUNTER, EVT_ON, EVT_OFF, EVT_BLINK, EVT_TOGGLE, EVT_TOGGLE_BLINK, ELSE, EVT_BRUP, EVT_BRDN }; // BRUP/BRDN pseudo
+  enum { EVT_START = EVT_BLINK };
+
+  Atm_out( void ) : Machine(){};
+  Atm_out& begin( int attached_pin, bool activeLow,
+          EthernetUDP& udpRef, OSCBundle& bndl, const char* address  );
+  Atm_out& blink( void );
+  Atm_out& blink( uint32_t duration );
+  Atm_out& blink( uint32_t duration, uint32_t pause_duration, uint16_t repeat_count = ATM_COUNTER_OFF );
+  Atm_out& pwm( uint16_t width, float freq = -1 );
+  Atm_out& frequency( float freq );
+  Atm_out& pause( uint32_t duration );
+  Atm_out& fade( int fade );
+  Atm_out& lead( uint32_t ms );
+  Atm_out& repeat( uint16_t repeat );
+  int brightness( int level = -1 );
+  Atm_out& on( void );
+  Atm_out& off( void );
+  Atm_out& toggle( void );
+  Atm_out& toggleBlink( void );
+  Atm_out& start( void );
+  Atm_out& trace( Stream& stream );
+  Atm_out& onFinish( Machine& machine, int event = 0 );
+  Atm_out& onFinish( atm_cb_push_t callback, int idx = 0 );
+  Atm_out& range( int toLow, int toHigh, bool wrap = false );
+  Atm_out& levels( unsigned char* map, int mapsize, bool wrap = false );
+  int brighten( int v = 1 );
+  Atm_out& trigger( int event );
+
+  const char* _adress = "/OSC";
+  EthernetUDP* _udpRef ;
+  Atm_out& onOSC(OSCMessage& msg );
+  OSCBundle* _bndl;
+
+
+ private:
+  enum { ENT_INIT, ENT_ON, ENT_OFF, EXT_CHAIN };
+  uint8_t level;
+  short pin;
+  bool activeLow;
+  uint8_t toHigh, toLow;
+  bool wrap;
+  uint16_t repeat_count;
+  uint16_t width;
+  float freq;
+  atm_timer_millis on_timer, off_timer, lead_timer;
+  atm_counter counter;
+  atm_connector onfinish;
+  unsigned char* levelMap;
+  int levelMapSize;
+  int mapLevel( int level );
+
+
+  int event( int id );
+  void action( int id );
+};