diff --git a/components/DendoStepper/DendoStepper.cpp b/components/DendoStepper/DendoStepper.cpp
index 40fa8ad..07d31aa 100644
--- a/components/DendoStepper/DendoStepper.cpp
+++ b/components/DendoStepper/DendoStepper.cpp
@@ -55,9 +55,6 @@ void DendoStepper::init(uint8_t stepP, uint8_t dirP, uint8_t enP, timer_group_t
 
 void DendoStepper::init()
 {
-    ESP_LOGW("DendoStepper", "semaphore init");
-    semaphore_isrVariables = xSemaphoreCreateBinary();
-    xSemaphoreGive(semaphore_isrVariables);
     uint64_t mask = (1ULL << conf.stepPin) | (1ULL << conf.dirPin) | (1ULL << conf.enPin); // put output gpio pins in bitmask
     gpio_config_t gpio_conf = {
         // config gpios
@@ -117,36 +114,39 @@ timer_avail:
     ESP_ERROR_CHECK(timer_isr_callback_add(conf.timer_group, conf.timer_idx, xISRwrap, this, 0)); // add callback fn to run when alarm is triggrd
 }
 
-
 esp_err_t DendoStepper::runPos(int32_t relative)
 {
     //TODO only enable when actually moving
     if (ctrl.status == DISABLED) // if motor is disabled, enable it
         enableMotor();
 
-    setDir(relative < 0); // set CCW if <0, else set CW
-
     if (!relative) // why would u call it with 0 wtf
         return ESP_ERR_NOT_SUPPORTED;
 
     if (ctrl.status > IDLE) { //currently moving
-        //ctrl.status = ctrl.status==COAST ? COAST : ACC; //stay at coast otherwise switch to ACC
-        ctrl.stepsRemaining = ctrl.stepsToGo - ctrl.stepCnt; 
-        calc(abs(relative) + ctrl.stepsRemaining); //calculate new velolcity profile for new+remaining steps
-        ESP_LOGW("DendoStepper", "EXTEND running movement (stepsRemaining: %d + stepsNew: %d  - current state: %d)", ctrl.stepsRemaining, abs(relative), (int)ctrl.status);
-        ESP_ERROR_CHECK(timer_set_alarm_value(conf.timer_group, conf.timer_idx, ctrl.stepInterval)); // set HW timer alarm to stepinterval
+        bool newDir = (relative < 0); // CCW if <0, else set CW
+        if (ctrl.dir == newDir){ //current direction is the same
+            ctrl.statusPrev = ctrl.status; //update previous status
+            ctrl.status = ctrl.status==COAST ? COAST : ACC; //stay at coast otherwise switch to ACC
+            calc(abs(relative + ctrl.stepsRemaining)); //calculate new velolcity profile for new+remaining steps
+        } else { //direction has changed
+                 //direction change not supported TODO wait for decel finish / queue?
+            STEP_LOGW("DendoStepper", "DIRECTION HOT-CHANGE NOT SUPPORTED - Finising previous move, this command will be ignored");
+            return ESP_ERR_NOT_SUPPORTED;
+        }
     }
-
     else { //current state is IDLE
-           //ctrl.statusPrev = ctrl.status; //update previous status
-        calc(abs(relative));                                                                         // calculate velocity profile
+        ctrl.statusPrev = ctrl.status; //update previous status
         ctrl.status = ACC;
-        ESP_ERROR_CHECK(timer_set_alarm_value(conf.timer_group, conf.timer_idx, ctrl.stepInterval)); // set HW timer alarm to stepinterval
-        ESP_ERROR_CHECK(timer_start(conf.timer_group, conf.timer_idx));                              // start the timer
+        setDir(relative < 0); // set CCW if <0, else set CW
+        calc(abs(relative));                                                                         // calculate velocity profile
     }
 
-    //printf("runpos end -- steps: %d, status: %d, olddir: %d, newdir: %d\n", relative, ctrl.status, ctrl.dir, newDir);
     currentPos += relative; //(target position / not actual)
+    ESP_ERROR_CHECK(timer_set_alarm_value(conf.timer_group, conf.timer_idx, ctrl.stepInterval)); // set HW timer alarm to stepinterval
+                                                                                                 //TODO timer has to be stopped before update if already running?
+    ESP_ERROR_CHECK(timer_start(conf.timer_group, conf.timer_idx));                              // start the timer
+
     return ESP_OK;
 }
 
@@ -159,31 +159,26 @@ esp_err_t DendoStepper::runPosMm(int32_t relative)
     return runPos(relative * ctrl.stepsPerMm);
 }
 
-//customized: if already running and direction is the same immediately pass to runPos
 esp_err_t DendoStepper::runAbs(uint32_t position)
 {
-    //exit if nothing to do
-    if (position == currentPos) return 0; //already at position
+    if (getState() > IDLE) // we are already moving, so stop it
+        stop();
+    while (getState() > IDLE)
+    {
+        // waiting for idle, watchdog should take care of inf loop if it occurs
+        vTaskDelay(1);
+    } // shouldnt take long tho
+
+    if (position == currentPos) // we cant go anywhere
+        return 0;
 
-    //calculate steps necessary
     int32_t relativeSteps = 0;
     relativeSteps = (int32_t)position - currentPos;
 
-    //wait if direction needs to change
-    if (getState() > IDLE){//already moving
-        bool newDir = (relativeSteps < 0); // CCW if <0, else set CW
-        if (ctrl.dir != newDir){ //direction differs 
-            STEP_LOGE("DendoStepper", "DIRECTION HOT-CHANGE NOT SUPPORTED - Waiting for move to finish...");
-            while (getState() > IDLE) vTaskDelay(5); //wait for move to finish
-        }
-    }
-
-    //call runPos with new target position
     ESP_LOGI("DendoStepper", "Cur: %llu move %d", currentPos, relativeSteps);
     return runPos(relativeSteps); // run to new position
 }
 
-
 esp_err_t DendoStepper::runAbsMm(uint32_t position)
 {
     if (ctrl.stepsPerMm == 0)
@@ -311,7 +306,7 @@ void DendoStepper::stop()
     }
     ctrl.runInfinite = false;
     timer_pause(conf.timer_group, conf.timer_idx); // stop the timer
-    //ctrl.statusPrev = ctrl.status; //update previous status
+    ctrl.statusPrev = ctrl.status; //update previous status
     ctrl.status = IDLE;
     ctrl.stepCnt = 0;
     gpio_set_level((gpio_num_t)conf.stepPin, 0);
@@ -338,23 +333,20 @@ bool DendoStepper::xISR()
 
     ctrl.stepCnt++;
 
-    ////CUSTOM: track actual precice current position
-    //if (ctrl.dir) {
-    //    ctrl.posActual ++;
-    //} else {
-    //    ctrl.posActual --;
-    //}
-    
+    //CUSTOM: track actual precice current position
+    if (ctrl.dir) {
+        ctrl.posActual ++;
+    } else {
+        ctrl.posActual --;
+    }
     //CUSTOM: track remaining steps for eventually resuming
-    //xSemaphoreTake(semaphore_isrVariables, portMAX_DELAY);
-    //ctrl.stepsRemaining = ctrl.stepCnt - ctrl.stepCnt; 
-    //xSemaphoreGive(semaphore_isrVariables);
+    ctrl.stepsRemaining = ctrl.stepCnt - ctrl.stepCnt; 
 
     // we are done
     if (ctrl.stepsToGo == ctrl.stepCnt && !ctrl.runInfinite)
     {
         timer_pause(conf.timer_group, conf.timer_idx); // stop the timer
-        //ctrl.statusPrev = ctrl.status; //update previous status
+        ctrl.statusPrev = ctrl.status; //update previous status
         ctrl.status = IDLE;
         ctrl.stepCnt = 0;
         return 0;
@@ -363,19 +355,19 @@ bool DendoStepper::xISR()
     if (ctrl.stepCnt > 0 && ctrl.stepCnt < ctrl.accEnd)
     { // we are accelerating
         ctrl.currentSpeed += ctrl.accInc;
-        //ctrl.statusPrev = ctrl.status; //update previous status
+        ctrl.statusPrev = ctrl.status; //update previous status
         ctrl.status = ACC; // we are accelerating, note that*/
     }
     else if (ctrl.stepCnt > ctrl.coastEnd && !ctrl.runInfinite)
     { // we must be deccelerating then
         ctrl.currentSpeed -= ctrl.decInc;
-        //ctrl.statusPrev = ctrl.status; //update previous status
+        ctrl.statusPrev = ctrl.status; //update previous status
         ctrl.status = DEC; // we are deccelerating
     }
     else
     {
         ctrl.currentSpeed = ctrl.targetSpeed;
-        //ctrl.statusPrev = ctrl.status; //update previous status
+        ctrl.statusPrev = ctrl.status; //update previous status
         ctrl.status = COAST; // we are coasting
     }
 
@@ -383,38 +375,25 @@ bool DendoStepper::xISR()
     // set alarm to calculated interval and disable pin
     GPIO.out_w1tc = (1ULL << conf.stepPin);
     timer_set_alarm_value(conf.timer_group, conf.timer_idx, ctrl.stepInterval);
+    ctrl.stepCnt++;
     return 1;
 }
 
 void DendoStepper::calc(uint32_t targetSteps)
 {
-	//only set initial speed if IDLE
-	if(ctrl.status == 1){
-		ctrl.currentSpeed = 0;
-		ESP_LOGD("DendoStepper", "calc-start: reset speed to 0 (start from idle) %lf\n", ctrl.currentSpeed);
-	}
-	else{
-		ESP_LOGD("DendoStepper", "calc start: NOT resetting speed (extend from ACC/DEC/COAST): %lf\n", ctrl.currentSpeed);
-	}
-    //CUSTOM reset counter if already moving
-    ctrl.stepCnt = 0; //FIXME bugs when set 0 while ISR reads/runs? mutex
-
     //steps from ctrl.speed -> 0:
     ctrl.decSteps = 0.5 * ctrl.dec * (ctrl.speed / ctrl.dec) * (ctrl.speed / ctrl.dec);
-	ESP_LOGD("DendoStepper", "decSteps: %d  currspeed: %lf,  ctrlSpeed: %lf\n", ctrl.decSteps, ctrl.currentSpeed,  ctrl.speed);
     //steps from 0 -> ctrl.speed:
     //ctrl.accSteps = 0.5 * ctrl.acc * (ctrl.speed / ctrl.acc) * (ctrl.speed / ctrl.acc);
     //steps from ctrl.currentSpeed -> ctrl.speed:
     ctrl.accSteps = 0.5 * ctrl.acc * (ctrl.speed / ctrl.acc) * (ctrl.speed / ctrl.acc)  * (ctrl.speed - ctrl.currentSpeed) / ctrl.speed;
-	ESP_LOGD("DendoStepper", "accSteps: %d  currspeed: %lf,  ctrlSpeed: %lf\n", ctrl.accSteps, ctrl.currentSpeed,  ctrl.speed);
 
     if (targetSteps < (ctrl.decSteps + ctrl.accSteps))
     {
         ESP_LOGI("Dendostepper", "Computing new speed");
 
         ctrl.speed = sqrt(2 * targetSteps * ((ctrl.dec * ctrl.acc) / (ctrl.dec + ctrl.acc)));
-        //ctrl.accSteps = 0.5 * ctrl.acc * (ctrl.speed / ctrl.acc) * (ctrl.speed / ctrl.acc);
-        ctrl.accSteps = 0.5 * ctrl.acc * (ctrl.speed / ctrl.acc) * (ctrl.speed / ctrl.acc)  * (ctrl.speed - ctrl.currentSpeed) / ctrl.speed;
+        ctrl.accSteps = 0.5 * ctrl.acc * (ctrl.speed / ctrl.acc) * (ctrl.speed / ctrl.acc);
         ctrl.decSteps = 0.5 * ctrl.dec * (ctrl.speed / ctrl.dec) * (ctrl.speed / ctrl.dec);
     }
 
@@ -422,27 +401,13 @@ void DendoStepper::calc(uint32_t targetSteps)
     ctrl.coastEnd = targetSteps - ctrl.decSteps;
     ctrl.targetSpeed = ctrl.speed;
 
-    ctrl.accInc = (ctrl.targetSpeed - ctrl.currentSpeed) / (double)ctrl.accSteps;
+    ctrl.accInc = ctrl.targetSpeed / (double)ctrl.accSteps;
     ctrl.decInc = ctrl.targetSpeed / (double)ctrl.decSteps;
 
-	//only set initial speed if IDLE
-	if(ctrl.status == 1){
-		ctrl.currentSpeed = ctrl.accInc;
-		ESP_LOGD("DendoStepper", "`reset curr speeed to accinc: %lf\n", ctrl.currentSpeed);
-		ESP_LOGD("DendoStepper", "status=%d setting speed to initial value: %lf\n",ctrl.status, ctrl.currentSpeed);
-	}
-	else{
-		ESP_LOGD("DendoStepper", "status=%d NOT resetting speed to initial value %lf\n",ctrl.status, ctrl.currentSpeed);
-	}
+    ctrl.currentSpeed = ctrl.accInc;
 
     ctrl.stepInterval = TIMER_F / ctrl.currentSpeed;
     ctrl.stepsToGo = targetSteps;
 
-	//debug log output
-	ESP_LOGD("DendoStepper", "accSteps: %d,  accInc: %lf, decSteps: %d, decInc: %lf", 
-			ctrl.accSteps, ctrl.accInc, ctrl.decSteps, ctrl.decInc);
-    ESP_LOGD("DendoStepper", "speedNow=%.1f, speedTarget=%.1f, accEnd=%d, coastEnd=%d,  accSteps=%d, accInc=%.3f\n",
-            ctrl.currentSpeed, ctrl.targetSpeed, ctrl.accEnd, ctrl.coastEnd, ctrl.accSteps, ctrl.accInc);
-    ESP_LOGD("DendoStepper", "acc end:%u coastend:%u stepstogo:%u speed:%f acc:%f int: %u",
-			ctrl.accEnd, ctrl.coastEnd, ctrl.stepsToGo, ctrl.speed, ctrl.acc, ctrl.stepInterval);
+    STEP_LOGI("calc", "acc end:%u coastend:%u stepstogo:%u speed:%f acc:%f int: %u", ctrl.accEnd, ctrl.coastEnd, ctrl.stepsToGo, ctrl.speed, ctrl.acc, ctrl.stepInterval);
 }
diff --git a/components/DendoStepper/include/DendoStepper.h b/components/DendoStepper/include/DendoStepper.h
index 9b535ad..a327ecc 100644
--- a/components/DendoStepper/include/DendoStepper.h
+++ b/components/DendoStepper/include/DendoStepper.h
@@ -29,7 +29,6 @@
 #include "freertos/task.h"
 #include "esp_timer.h"
 #include "math.h"
-#include "freertos/semphr.h"
 
 //#define STEP_DEBUG
 
@@ -96,7 +95,7 @@ typedef struct
     uint32_t accSteps = 0;
     uint32_t decSteps = 0;
     int32_t stepsRemaining = 0;
-    //uint64_t posActual = 0; //actual current pos incremented at every step
+    uint64_t posActual = 0; //actual current pos incremented at every step
     uint8_t statusPrev = DISABLED; //FIXME currently unused
     uint8_t status = DISABLED;
     bool dir = CW;
@@ -112,7 +111,6 @@ private:
     ctrl_var_t ctrl;
     esp_timer_handle_t dyingTimer;
     TaskHandle_t enTask;
-    SemaphoreHandle_t semaphore_isrVariables = NULL;
     uint64_t currentPos = 0; // absolute position
     bool timerStarted = 0;
 
diff --git a/main/guide-stepper.cpp b/main/guide-stepper.cpp
index f798d94..8dbd96b 100644
--- a/main/guide-stepper.cpp
+++ b/main/guide-stepper.cpp
@@ -11,7 +11,6 @@ extern "C"
 #include "config.hpp"
 #include "guide-stepper.hpp"
 #include "encoder.hpp"
-#include "gpio_evaluateSwitch.hpp"
 
 
 
@@ -24,7 +23,7 @@ extern "C"
 #define STEPPER_TEST_TRAVEL 65     //mm
                                    //
 #define MIN_MM 0
-#define MAX_MM 110 //60
+#define MAX_MM 60 
 #define POS_MAX_STEPS MAX_MM * STEPPER_STEPS_PER_MM
 #define POS_MIN_STEPS MIN_MM * STEPPER_STEPS_PER_MM
 
@@ -32,9 +31,8 @@ extern "C"
 #define SPEED_MIN 2.0   //mm/s
 #define SPEED_MAX 60.0 //mm/s
 
-#define SPEED 10 //35, 100, 50 rev
-#define ACCEL_MS 800.0  //ms from 0 to max
-#define DECEL_MS 500.0   //ms from max to 0
+#define ACCEL_MS 100.0  //ms from 0 to max
+#define DECEL_MS 90.0   //ms from max to 0
 
 #define STEPPER_STEPS_PER_ROT 1600
 #define STEPPER_STEPS_PER_MM STEPPER_STEPS_PER_ROT/4
@@ -72,10 +70,10 @@ void travelSteps(int stepsTarget){
     while (stepsToGo != 0){
 
         //--- wait if direction changed ---
-        //if (dirPrev != dir){
-        //        ESP_LOGW(TAG, " dir-change detected - waiting for move to finish \n ");
-        //        while(step.getState() != 1) vTaskDelay(1);  //wait for move to finish
-        //}
+        if (dirPrev != dir){
+                ESP_LOGI(TAG, " dir-change detected - waiting for move to finish \n ");
+                while(step.getState() != 1) vTaskDelay(1);  //wait for move to finish
+        }
 
         //--- currently moving right ---
         if (stepp_direction == true){               //currently moving right
@@ -189,57 +187,18 @@ void task_stepper_test(void *pvParameter)
 {
     init_stepper();
     home();
-    step.setSpeedMm(SPEED, ACCEL_MS, DECEL_MS);
-	//--- move from left to right repeatedly ---
-    // while (1) {
-    //     updateSpeedFromAdc();
-    //     step.runPosMm(STEPPER_TEST_TRAVEL);
-    //     while(step.getState() != 1) vTaskDelay(2);
-    //     ESP_LOGI(TAG, "finished moving right => moving left");
 
-    //  10updateSpeedFromAdc();
-    //     step.runPosMm(-STEPPER_TEST_TRAVEL);
-    //     while(step.getState() != 1) vTaskDelay(2); //1=idle
-    //     ESP_LOGI(TAG, "finished moving left => moving right");
-    // }
+    while (1) {
+        updateSpeedFromAdc();
+        step.runPosMm(STEPPER_TEST_TRAVEL);
+        while(step.getState() != 1) vTaskDelay(2);
+        ESP_LOGI(TAG, "finished moving right => moving left");
 
-	//--- control stepper using preset buttons ---
-	while(1){
-		vTaskDelay(20 / portTICK_PERIOD_MS);
-
-		//------ handle switches ------
-		//run handle functions for all switches
-		SW_START.handle();
-		SW_RESET.handle();
-		SW_SET.handle();
-		SW_PRESET1.handle();
-		SW_PRESET2.handle();
-		SW_PRESET3.handle();
-		SW_CUT.handle();
-		SW_AUTO_CUT.handle();
-
-		if (SW_RESET.risingEdge) {
-			ESP_LOGI(TAG, "button - stop stepper\n ");
-			buzzer.beep(1, 1000, 100);
-			step.stop();
-		}
-		if (SW_PRESET1.risingEdge) {
-			ESP_LOGI(TAG, "button - moving right\n ");
-			buzzer.beep(2, 300, 100);
-			step.setSpeedMm(SPEED, ACCEL_MS, DECEL_MS);
-			step.runPosMm(15);
-		}
-		if (SW_PRESET3.risingEdge) {
-			ESP_LOGI(TAG, "button - moving left\n ");
-			buzzer.beep(1, 500, 100);
-			step.setSpeedMm(SPEED, ACCEL_MS, DECEL_MS);
-			step.runPosMm(-15);
-		}
-		if (SW_PRESET2.risingEdge) {
-			buzzer.beep(1, 100, 100);
-			ESP_LOGW(TAG, "button - current state: %d\n, pos: %llu", (int)step.getState(), step.getPositionMm());
-		}
-	}
+        updateSpeedFromAdc();
+        step.runPosMm(-STEPPER_TEST_TRAVEL);
+        while(step.getState() != 1) vTaskDelay(2); //1=idle
+        ESP_LOGI(TAG, "finished moving left => moving right");
+    }
 }
 
 
@@ -276,8 +235,6 @@ void task_stepper_ctl(void *pvParameter)
         //read potentiometer and normalize (0-1) to get a variable for testing
         potiModifier = (float) gpio_readAdc(ADC_CHANNEL_POTI) / 4095; //0-4095 -> 0-1
         //ESP_LOGI(TAG, "current poti-modifier = %f", potiModifier);
-        ESP_LOGI(TAG, "delaying stepper-ctl task by %.1f ms (poti value)", 2000 * potiModifier);
-        vTaskDelay(2000 * potiModifier / portTICK_PERIOD_MS);
 
         //calculate steps to move
         cableLen = (double)encStepsDelta * 1000 / ENCODER_STEPS_PER_METER;
@@ -293,7 +250,7 @@ void task_stepper_ctl(void *pvParameter)
             ESP_LOGD(TAG, "cablelen=%.2lf, turns=%.2lf, travelMm=%.3lf, travelStepsExact: %.3lf, travelStepsFull=%d, partialStep=%.3lf", cableLen, turns, travelMm, travelStepsExact, travelStepsFull, travelStepsPartial);
             ESP_LOGI(TAG, "MOVING %d steps", travelStepsFull);
             //TODO: calculate variable speed for smoother movement? for example intentionally lag behind and calculate speed according to buffered data
-            step.setSpeedMm(SPEED, ACCEL_MS, DECEL_MS);
+            step.setSpeedMm(35, 100, 50);
             //testing: get speed from poti
             //step.setSpeedMm(35, 1000*potiModifier+1, 1000*potiModifier+1);
             travelSteps(travelStepsExact);
diff --git a/main/main.cpp b/main/main.cpp
index 18cdc5b..7872214 100644
--- a/main/main.cpp
+++ b/main/main.cpp
@@ -87,7 +87,7 @@ extern "C" void app_main()
     esp_log_level_set("switches-analog", ESP_LOG_WARN);
     esp_log_level_set("control", ESP_LOG_INFO);
     esp_log_level_set("stepper", ESP_LOG_DEBUG);
-    esp_log_level_set("DendoStepper", ESP_LOG_DEBUG); //stepper lib
+    esp_log_level_set("Dendostepper", ESP_LOG_WARN); //stepper lib
     esp_log_level_set("calc", ESP_LOG_WARN); //stepper lib
 
 #ifdef STEPPER_TEST
@@ -98,11 +98,11 @@ extern "C" void app_main()
     xTaskCreate(task_control, "task_control", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL);
 
     //create task for controlling the machine
-    xTaskCreate(task_stepper_ctl, "task_stepper_ctl", configMINIMAL_STACK_SIZE * 5, NULL, 5, NULL);
-#endif
+    xTaskCreate(task_stepper_ctl, "task_stepper_ctl", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL);
 
     //create task for handling the buzzer
     xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL);
+#endif
 
     //beep at startup
     buzzer.beep(3, 70, 50);