Stepper driver from scratch, test with buttons - WIP

- Add stepper driver code from scratch
- Remove / comment out code that used DendoStepper library
- Test custom driver with buttons (guide-stepper.cpp)

untested limited features
This commit is contained in:
jonny_l480 2023-04-10 22:28:18 +02:00
parent a0032ea07f
commit 1d53d3467c
6 changed files with 380 additions and 156 deletions

View File

@ -8,6 +8,7 @@ idf_component_register(
"display.cpp" "display.cpp"
"cutter.cpp" "cutter.cpp"
"switchesAnalog.cpp" "switchesAnalog.cpp"
"stepper.cpp"
"guide-stepper.cpp" "guide-stepper.cpp"
"encoder.cpp" "encoder.cpp"
INCLUDE_DIRS INCLUDE_DIRS

View File

@ -85,7 +85,7 @@ extern "C" {
//----- stepper config ----- //----- stepper config -----
//-------------------------- //--------------------------
//enable stepper test mode (dont start control and encoder task) //enable stepper test mode (dont start control and encoder task)
//#define STEPPER_TEST #define STEPPER_TEST
#define STEPPER_STEP_PIN GPIO_NUM_18 //mos1 #define STEPPER_STEP_PIN GPIO_NUM_18 //mos1
#define STEPPER_DIR_PIN GPIO_NUM_16 //ST3 #define STEPPER_DIR_PIN GPIO_NUM_16 //ST3
#define STEPPER_EN_PIN GPIO_NUM_0 //not connected (-> stepper always on) #define STEPPER_EN_PIN GPIO_NUM_0 //not connected (-> stepper always on)

View File

@ -7,7 +7,7 @@ extern "C"
#include "driver/adc.h" #include "driver/adc.h"
} }
#include "DendoStepper.h" #include "stepper.hpp"
#include "config.hpp" #include "config.hpp"
#include "guide-stepper.hpp" #include "guide-stepper.hpp"
#include "encoder.hpp" #include "encoder.hpp"
@ -46,7 +46,6 @@ extern "C"
//---------------------- //----------------------
//----- variables ------ //----- variables ------
//---------------------- //----------------------
static DendoStepper step;
static const char *TAG = "stepper"; //tag for logging static const char *TAG = "stepper"; //tag for logging
static bool stepp_direction = true; static bool stepp_direction = true;
@ -57,96 +56,98 @@ static uint32_t posNow = 0;
//---------------------- //----------------------
//----- functions ------ //----- functions ------
//---------------------- //----------------------
//move axis certain Steps (relative) between left and right or reverse when negative ////move axis certain Steps (relative) between left and right or reverse when negative
void travelSteps(int stepsTarget){ //void travelSteps(int stepsTarget){
//posNow = step.getPositionMm(); //not otherwise controlled, so no update necessary // //posNow = step.getPositionMm(); //not otherwise controlled, so no update necessary
int stepsToGo, remaining; // int stepsToGo, remaining;
//
stepsToGo = abs(stepsTarget); // stepsToGo = abs(stepsTarget);
if(stepsTarget < 0) stepp_direction = !stepp_direction; //invert direction in reverse mode // if(stepsTarget < 0) stepp_direction = !stepp_direction; //invert direction in reverse mode
//
while (stepsToGo != 0){ // while (stepsToGo != 0){
//--- currently moving right --- // //--- currently moving right ---
if (stepp_direction == true){ //currently moving right // if (stepp_direction == true){ //currently moving right
remaining = POS_MAX_STEPS - posNow; //calc remaining distance fom current position to limit // remaining = POS_MAX_STEPS - posNow; //calc remaining distance fom current position to limit
if (stepsToGo > remaining){ //new distance will exceed limit // if (stepsToGo > remaining){ //new distance will exceed limit
step.runAbs (POS_MAX_STEPS); //move to limit // //....step.runAbs (POS_MAX_STEPS); //move to limit
while(step.getState() != 1) vTaskDelay(1); //wait for move to finish // //....while(step.getState() != 1) vTaskDelay(1); //wait for move to finish
posNow = POS_MAX_STEPS; // posNow = POS_MAX_STEPS;
stepp_direction = false; //change current direction for next iteration // stepp_direction = false; //change current direction for next iteration
stepsToGo = stepsToGo - remaining; //decrease target length by already traveled distance // stepsToGo = stepsToGo - remaining; //decrease target length by already traveled distance
ESP_LOGI(TAG, " --- moved to max -> change direction (L) --- \n "); // ESP_LOGI(TAG, " --- moved to max -> change direction (L) --- \n ");
} // }
else { //target distance does not reach the limit // else { //target distance does not reach the limit
step.runAbs (posNow + stepsToGo); //move by (remaining) distance to reach target length // //....step.runAbs (posNow + stepsToGo); //move by (remaining) distance to reach target length
while(step.getState() != 1) vTaskDelay(1); //wait for move to finish // //....while(step.getState() != 1) vTaskDelay(1); //wait for move to finish
ESP_LOGD(TAG, "moving to %d\n", posNow+stepsToGo); // ESP_LOGD(TAG, "moving to %d\n", posNow+stepsToGo);
posNow += stepsToGo; // posNow += stepsToGo;
stepsToGo = 0; //finished, reset target length (could as well exit loop/break) // stepsToGo = 0; //finished, reset target length (could as well exit loop/break)
} // }
} // }
//
//--- currently moving left --- // //--- currently moving left ---
else { // else {
remaining = posNow - POS_MIN_STEPS; // remaining = posNow - POS_MIN_STEPS;
if (stepsToGo > remaining){ // if (stepsToGo > remaining){
step.runAbs (POS_MIN_STEPS); // //....step.runAbs (POS_MIN_STEPS);
while(step.getState() != 1) vTaskDelay(2); //wait for move to finish // //....while(step.getState() != 1) vTaskDelay(2); //wait for move to finish
posNow = POS_MIN_STEPS; // posNow = POS_MIN_STEPS;
stepp_direction = true; // stepp_direction = true;
stepsToGo = stepsToGo - remaining; // stepsToGo = stepsToGo - remaining;
ESP_LOGI(TAG, " --- moved to min -> change direction (R) --- \n "); // ESP_LOGI(TAG, " --- moved to min -> change direction (R) --- \n ");
} // }
else { // else {
step.runAbs (posNow - stepsToGo); //when moving left the coordinate has to be decreased // //....step.runAbs (posNow - stepsToGo); //when moving left the coordinate has to be decreased
while(step.getState() != 1) vTaskDelay(2); //wait for move to finish // while(step.getState() != 1) vTaskDelay(2); //wait for move to finish
ESP_LOGD(TAG, "moving to %d\n", posNow - stepsToGo); // ESP_LOGD(TAG, "moving to %d\n", posNow - stepsToGo);
posNow -= stepsToGo; // posNow -= stepsToGo;
stepsToGo = 0; // stepsToGo = 0;
} // }
} // }
} // }
if(stepsTarget < 0) stepp_direction = !stepp_direction; //undo inversion of stepp_direction after reverse mode is finished // if(stepsTarget < 0) stepp_direction = !stepp_direction; //undo inversion of stepp_direction after reverse mode is finished
return; // return;
} //}
//
//
//move axis certain Mm (relative) between left and right or reverse when negative ////move axis certain Mm (relative) between left and right or reverse when negative
void travelMm(int length){ //void travelMm(int length){
travelSteps(length * STEPPER_STEPS_PER_MM); // travelSteps(length * STEPPER_STEPS_PER_MM);
} //}
//
//
//define zero/start position ////define zero/start position
//currently crashes into hardware limitation for certain time ////currently crashes into hardware limitation for certain time
//TODO: limit switch ////TODO: limit switch
void home() { //void home() {
ESP_LOGW(TAG, "auto-home..."); // ESP_LOGW(TAG, "auto-home...");
step.setSpeedMm(100, 500, 10); // //....step.setSpeedMm(100, 500, 10);
step.runInf(1); // //....step.runInf(1);
vTaskDelay(1500 / portTICK_PERIOD_MS); // vTaskDelay(1500 / portTICK_PERIOD_MS);
step.stop(); // //....step.stop();
step.resetAbsolute(); // //....step.resetAbsolute();
ESP_LOGW(TAG, "auto-home finished"); // ESP_LOGW(TAG, "auto-home finished");
} //}
//initialize/configure stepper instance //initialize/configure stepper instance
void init_stepper() { void init_stepper() {
ESP_LOGW(TAG, "initializing stepper..."); // ESP_LOGW(TAG, "initializing stepper...");
DendoStepper_config_t step_cfg = { // DendoStepper_config_t step_cfg = {
.stepPin = STEPPER_STEP_PIN, // .stepPin = STEPPER_STEP_PIN,
.dirPin = STEPPER_DIR_PIN, // .dirPin = STEPPER_DIR_PIN,
.enPin = STEPPER_EN_PIN, // .enPin = STEPPER_EN_PIN,
.timer_group = TIMER_GROUP_0, // .timer_group = TIMER_GROUP_0,
.timer_idx = TIMER_0, // .timer_idx = TIMER_0,
.miStep = MICROSTEP_32, // .miStep = MICROSTEP_32,
.stepAngle = 1.8}; // .stepAngle = 1.8};
step.config(&step_cfg); // //....step.config(&step_cfg);
step.init(); // //....step.init();
//
// //....step.setSpeed(1000, 1000, 1000); //random default speed
// //....step.setStepsPerMm(STEPPER_STEPS_PER_MM); //guide: 4mm/rot
step.setSpeed(1000, 1000, 1000); //random default speed stepper_init();
step.setStepsPerMm(STEPPER_STEPS_PER_MM); //guide: 4mm/rot
} }
@ -155,7 +156,7 @@ void updateSpeedFromAdc() {
int potiRead = gpio_readAdc(ADC_CHANNEL_POTI); //0-4095 GPIO34 int potiRead = gpio_readAdc(ADC_CHANNEL_POTI); //0-4095 GPIO34
double poti = potiRead/4095.0; double poti = potiRead/4095.0;
int speed = poti*(SPEED_MAX-SPEED_MIN) + SPEED_MIN; int speed = poti*(SPEED_MAX-SPEED_MIN) + SPEED_MIN;
step.setSpeedMm(speed, ACCEL_MS, DECEL_MS); //....step.setSpeedMm(speed, ACCEL_MS, DECEL_MS);
ESP_LOGW(TAG, "poti: %d (%.2lf%%), set speed to: %d", potiRead, poti*100, speed); ESP_LOGW(TAG, "poti: %d (%.2lf%%), set speed to: %d", potiRead, poti*100, speed);
} }
@ -166,80 +167,99 @@ void updateSpeedFromAdc() {
//---------------------------- //----------------------------
void task_stepper_test(void *pvParameter) void task_stepper_test(void *pvParameter)
{ {
init_stepper(); stepper_init();
home(); while(1){
vTaskDelay(20 / portTICK_PERIOD_MS);
while (1) { //------ handle switches ------
updateSpeedFromAdc(); //run handle functions for all switches
step.runPosMm(STEPPER_TEST_TRAVEL); SW_START.handle();
while(step.getState() != 1) vTaskDelay(2); SW_RESET.handle();
ESP_LOGI(TAG, "finished moving right => moving left"); SW_SET.handle();
SW_PRESET1.handle();
SW_PRESET2.handle();
SW_PRESET3.handle();
SW_CUT.handle();
SW_AUTO_CUT.handle();
updateSpeedFromAdc(); if (SW_RESET.risingEdge) {
step.runPosMm(-STEPPER_TEST_TRAVEL); stepper_toggleDirection();
while(step.getState() != 1) vTaskDelay(2); //1=idle buzzer.beep(1, 1000, 100);
ESP_LOGI(TAG, "finished moving left => moving right"); }
} if (SW_PRESET1.risingEdge) {
buzzer.beep(2, 300, 100);
stepper_setTargetSteps(100);
}
if (SW_PRESET2.risingEdge) {
buzzer.beep(1, 500, 100);
stepper_setTargetSteps(1000);
}
if (SW_PRESET3.risingEdge) {
buzzer.beep(1, 100, 100);
stepper_setTargetSteps(6000);
}
}
} }
//---------------------------- //----------------------------
//----- TASK stepper-ctl ----- //----- TASK stepper-ctl -----
//---------------------------- //----------------------------
void task_stepper_ctl(void *pvParameter) void task_stepper_ctl(void *pvParameter)
{ {
//variables // //variables
int encStepsNow = 0; //get curret steps of encoder // int encStepsNow = 0; //get curret steps of encoder
int encStepsPrev = 0; //steps at last check // int encStepsPrev = 0; //steps at last check
int encStepsDelta = 0; //steps changed since last iteration // int encStepsDelta = 0; //steps changed since last iteration
//
double cableLen = 0; // double cableLen = 0;
double travelStepsExact = 0; //steps axis has to travel // double travelStepsExact = 0; //steps axis has to travel
double travelStepsPartial = 0; // double travelStepsPartial = 0;
int travelStepsFull = 0; // int travelStepsFull = 0;
double travelMm = 0; // double travelMm = 0;
double turns = 0; // double turns = 0;
//
float potiModifier; // float potiModifier;
//
init_stepper(); // init_stepper();
home(); // home();
//
while(1){ // while(1){
//get current length // //get current length
encStepsNow = encoder_getSteps(); // encStepsNow = encoder_getSteps();
//
//calculate change // //calculate change
encStepsDelta = encStepsNow - encStepsPrev; //FIXME MAJOR BUG: when resetting encoder/length in control task, diff will be huge! // encStepsDelta = encStepsNow - encStepsPrev; //FIXME MAJOR BUG: when resetting encoder/length in control task, diff will be huge!
//
//read potentiometer and normalize (0-1) to get a variable for testing // //read potentiometer and normalize (0-1) to get a variable for testing
potiModifier = (float) gpio_readAdc(ADC_CHANNEL_POTI) / 4095; //0-4095 -> 0-1 // potiModifier = (float) gpio_readAdc(ADC_CHANNEL_POTI) / 4095; //0-4095 -> 0-1
//ESP_LOGI(TAG, "current poti-modifier = %f", potiModifier); // //ESP_LOGI(TAG, "current poti-modifier = %f", potiModifier);
//
//calculate steps to move // //calculate steps to move
cableLen = (double)encStepsDelta * 1000 / ENCODER_STEPS_PER_METER; // cableLen = (double)encStepsDelta * 1000 / ENCODER_STEPS_PER_METER;
turns = cableLen / (PI * D_REEL); // turns = cableLen / (PI * D_REEL);
travelMm = turns * D_CABLE; // travelMm = turns * D_CABLE;
travelStepsExact = travelMm * STEPPER_STEPS_PER_MM + travelStepsPartial; //convert mm to steps and add not moved partial steps // travelStepsExact = travelMm * STEPPER_STEPS_PER_MM + travelStepsPartial; //convert mm to steps and add not moved partial steps
travelStepsPartial = 0; // travelStepsPartial = 0;
travelStepsFull = (int)travelStepsExact; // travelStepsFull = (int)travelStepsExact;
//
//move axis when ready to move at least 1 step // //move axis when ready to move at least 1 step
if (abs(travelStepsFull) > 1){ // if (abs(travelStepsFull) > 1){
travelStepsPartial = fmod(travelStepsExact, 1); //save remaining partial steps to be added in the next iteration // travelStepsPartial = fmod(travelStepsExact, 1); //save remaining partial steps to be added in the next iteration
ESP_LOGD(TAG, "cablelen=%.2lf, turns=%.2lf, travelMm=%.3lf, travelStepsExact: %.3lf, travelStepsFull=%d, partialStep=%.3lf", cableLen, turns, travelMm, travelStepsExact, travelStepsFull, travelStepsPartial); // 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); // 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 // //TODO: calculate variable speed for smoother movement? for example intentionally lag behind and calculate speed according to buffered data
step.setSpeedMm(35, 100, 50); // //....step.setSpeedMm(35, 100, 50);
//testing: get speed from poti // //testing: get speed from poti
//step.setSpeedMm(35, 1000*potiModifier+1, 1000*potiModifier+1); // //step.setSpeedMm(35, 1000*potiModifier+1, 1000*potiModifier+1);
travelSteps(travelStepsExact); // travelSteps(travelStepsExact);
encStepsPrev = encStepsNow; //update previous length // encStepsPrev = encStepsNow; //update previous length
} // }
else { // else {
//TODO use encoder queue to only run this check at encoder event? // //TODO use encoder queue to only run this check at encoder event?
vTaskDelay(2); // vTaskDelay(2);
} // }
} // }
} }

View File

@ -97,12 +97,12 @@ extern "C" void app_main()
//create task for controlling the machine //create task for controlling the machine
xTaskCreate(task_control, "task_control", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL); xTaskCreate(task_control, "task_control", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL);
//create task for controlling the machine //create task for controlling the stepper
xTaskCreate(task_stepper_ctl, "task_stepper_ctl", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL); xTaskCreate(task_stepper_ctl, "task_stepper_ctl", configMINIMAL_STACK_SIZE * 3, NULL, 5, NULL);
#endif
//create task for handling the buzzer //create task for handling the buzzer
xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL); xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL);
#endif
//beep at startup //beep at startup
buzzer.beep(3, 70, 50); buzzer.beep(3, 70, 50);

163
main/stepper.cpp Normal file
View File

@ -0,0 +1,163 @@
//custom driver for stepper motor
#include "config.hpp"
//config from config.hpp
//#define STEPPER_STEP_PIN GPIO_NUM_18 //mos1
//#define STEPPER_DIR_PIN GPIO_NUM_16 //ST3
//
extern "C" {
#include "driver/timer.h"
#include "driver/gpio.h"
}
#define TIMER_F 1000000ULL
#define TICK_PER_S TIMER_S
#define NS_TO_T_TICKS(x) (x)
static const char *TAG = "stepper-ctl"; //tag for logging
bool direction = 0;
bool timer_isr(void *arg);
typedef struct {
int targetSteps; // Target step count
int currentSteps; // Current step count
int acceleration; // Acceleration (in steps per second^2)
int deceleration; // Deceleration (in steps per second^2)
gpio_num_t pulsePin; // Pin for pulse signal
gpio_num_t directionPin; // Pin for direction signal
timer_group_t timerGroup; // Timer group
timer_idx_t timerIdx; // Timer index
bool isAccelerating; // Flag to indicate if accelerating
bool isDecelerating; // Flag to indicate if decelerating
int initialSpeed; // Initial speed (in steps per second)
int targetSpeed; // Target speed (in steps per second)
int currentSpeed; // Current speed (in steps per second)
} StepperControl;
StepperControl ctrl; // Create an instance of StepperControl struct
void stepper_setTargetSteps(int steps){
ESP_LOGW(TAG, "set target steps to %d", steps);
//TODO switch dir pin in isr? not in sync with count
if(steps < 0){
gpio_set_level(ctrl.directionPin, 1);
} else {
gpio_set_level(ctrl.directionPin, 0);
}
ctrl.targetSteps = abs(steps);
}
void stepper_toggleDirection(){
direction = !direction;
gpio_set_level(ctrl.directionPin, 1);
ESP_LOGW(TAG, "toggle direction -> %d", direction);
}
void stepper_init(){
ESP_LOGW(TAG, "init - configure struct...");
// Set values in StepperControl struct
ctrl.targetSteps = 0;
ctrl.currentSteps = 0;
ctrl.acceleration = 50;
ctrl.deceleration = 50;
ctrl.pulsePin = STEPPER_STEP_PIN;
ctrl.directionPin = STEPPER_DIR_PIN;
ctrl.timerGroup = TIMER_GROUP_0;
ctrl.timerIdx = TIMER_0;
ctrl.isAccelerating = true;
ctrl.isDecelerating = false;
ctrl.initialSpeed = 0; // Set initial speed as needed
ctrl.targetSpeed = 500; // Set target speed as needed
ctrl.currentSpeed = ctrl.initialSpeed;
// Configure pulse and direction pins as outputs
ESP_LOGW(TAG, "init - configure gpio pins...");
gpio_set_direction(ctrl.pulsePin, GPIO_MODE_OUTPUT);
gpio_set_direction(ctrl.directionPin, GPIO_MODE_OUTPUT);
ESP_LOGW(TAG, "init - initialize/configure timer...");
timer_config_t timer_conf = {
.alarm_en = TIMER_ALARM_EN, // we need alarm
.counter_en = TIMER_PAUSE, // dont start now lol
.intr_type = TIMER_INTR_LEVEL, // interrupt
.counter_dir = TIMER_COUNT_UP, // count up duh
.auto_reload = TIMER_AUTORELOAD_EN, // reload pls
.divider = 80000000ULL / TIMER_F, // ns resolution
};
ESP_ERROR_CHECK(timer_init(ctrl.timerGroup, ctrl.timerIdx, &timer_conf)); // init the timer
ESP_ERROR_CHECK(timer_set_counter_value(ctrl.timerGroup, ctrl.timerIdx, 0)); // set it to 0
//ESP_ERROR_CHECK(timer_isr_callback_add(ctrl.timerGroup, ctrl.timerIdx, timer_isr, )); // add callback fn to run when alarm is triggrd
ESP_ERROR_CHECK(timer_isr_callback_add(ctrl.timerGroup, ctrl.timerIdx, timer_isr, (void *)ctrl.timerIdx, 0));
}
bool timer_isr(void *arg) {
// Cast arg to an integer type that has the same size as timer_idx_t
uintptr_t arg_val = (uintptr_t)arg;
// Cast arg_val to timer_idx_t
timer_idx_t timer_idx = (timer_idx_t)arg_val;
int32_t step_diff = ctrl.targetSteps - ctrl.currentSteps;
if (timer_idx == ctrl.timerIdx) {
if (ctrl.currentSteps < ctrl.targetSteps) {
// Check if accelerating
if (ctrl.isAccelerating) {
if (ctrl.currentSpeed < ctrl.targetSpeed) {
// Increase speed if not yet at target speed
ctrl.currentSpeed += ctrl.acceleration;
} else {
// Reached target speed, clear accelerating flag
ctrl.isAccelerating = false;
}
}
// Check if decelerating
if (ctrl.isDecelerating) {
if (ctrl.currentSpeed > ctrl.targetSpeed) {
// Decrease speed if not yet at target speed
ctrl.currentSpeed -= ctrl.deceleration;
} else {
// Reached target speed, clear decelerating flag
ctrl.isDecelerating = false;
}
}
// Generate pulse for stepper motor
gpio_set_level(ctrl.pulsePin, 1);
ets_delay_us(500); // Adjust delay as needed
gpio_set_level(ctrl.pulsePin, 0);
// Update current step count
ctrl.currentSteps++;
// Update timer period based on current speed
timer_set_alarm_value(ctrl.timerGroup, ctrl.timerIdx, TIMER_BASE_CLK / ctrl.currentSpeed);
} else {
// Reached target step count, stop timer
timer_pause(ctrl.timerGroup, ctrl.timerIdx);
ESP_LOGW(TAG,"finished, pausing timer");
}
}
return 1;
}

40
main/stepper.hpp Normal file
View File

@ -0,0 +1,40 @@
void stepper_init();
void stepper_setTargetSteps(int steps);
void stepper_toggleDirection();
//typedef struct
//{
// uint8_t stepPin; /** step signal pin */
// uint8_t dirPin; /** dir signal pin */
// timer_group_t timer_group; /** timer group, useful if we are controlling more than 2 steppers */
// timer_idx_t timer_idx; /** timer index, useful if we are controlling 2steppers */
// float stepAngle; /** one step angle in degrees (usually 1.8deg), used in steps per rotation calculation */
//} stepper_config_t;
//
//typedef struct
//{
// uint32_t stepInterval = 40000; // step interval in ns/25
// double targetSpeed = 0; // target speed in steps/s
// double currentSpeed = 0;
// double accInc = 0;
// double decInc = 0;
// uint32_t stepCnt = 0; // step counter
// uint32_t accEnd; // when to end acc and start coast
// uint32_t coastEnd; // when to end coast and start decel
// uint32_t stepsToGo = 0; // steps we need to take
// float speed = 100; // speed in rad/s
// float acc = 100; // acceleration in rad*second^-2
// float dec = 100; // decceleration in rad*second^-2
// uint32_t accSteps = 0;
// uint32_t decSteps = 0;
// uint8_t status = DISABLED;
// bool dir = CW;
// bool runInfinite = false;
// uint16_t stepsPerRot; // steps per one revolution, 360/stepAngle * microstep
// uint16_t stepsPerMm = 0; /** Steps per one milimiter, if the motor is performing linear movement */
//} ctrl_var_t;