diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt index d2b02cb..1fd9e2c 100644 --- a/main/CMakeLists.txt +++ b/main/CMakeLists.txt @@ -8,6 +8,7 @@ idf_component_register( "display.cpp" "cutter.cpp" "switchesAnalog.cpp" + "stepper.cpp" "guide-stepper.cpp" "encoder.cpp" INCLUDE_DIRS diff --git a/main/config.hpp b/main/config.hpp index dcd474b..95ca28b 100644 --- a/main/config.hpp +++ b/main/config.hpp @@ -85,7 +85,7 @@ extern "C" { //----- stepper config ----- //-------------------------- //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_DIR_PIN GPIO_NUM_16 //ST3 #define STEPPER_EN_PIN GPIO_NUM_0 //not connected (-> stepper always on) diff --git a/main/guide-stepper.cpp b/main/guide-stepper.cpp index 37cd5de..25da8ea 100644 --- a/main/guide-stepper.cpp +++ b/main/guide-stepper.cpp @@ -7,7 +7,7 @@ extern "C" #include "driver/adc.h" } -#include "DendoStepper.h" +#include "stepper.hpp" #include "config.hpp" #include "guide-stepper.hpp" #include "encoder.hpp" @@ -46,7 +46,6 @@ extern "C" //---------------------- //----- variables ------ //---------------------- -static DendoStepper step; static const char *TAG = "stepper"; //tag for logging static bool stepp_direction = true; @@ -57,96 +56,98 @@ static uint32_t posNow = 0; //---------------------- //----- functions ------ //---------------------- -//move axis certain Steps (relative) between left and right or reverse when negative -void travelSteps(int stepsTarget){ - //posNow = step.getPositionMm(); //not otherwise controlled, so no update necessary - int stepsToGo, remaining; - - stepsToGo = abs(stepsTarget); - if(stepsTarget < 0) stepp_direction = !stepp_direction; //invert direction in reverse mode - - while (stepsToGo != 0){ - //--- currently moving right --- - if (stepp_direction == true){ //currently moving right - remaining = POS_MAX_STEPS - posNow; //calc remaining distance fom current position to limit - if (stepsToGo > remaining){ //new distance will exceed limit - step.runAbs (POS_MAX_STEPS); //move to limit - while(step.getState() != 1) vTaskDelay(1); //wait for move to finish - posNow = POS_MAX_STEPS; - stepp_direction = false; //change current direction for next iteration - stepsToGo = stepsToGo - remaining; //decrease target length by already traveled distance - ESP_LOGI(TAG, " --- moved to max -> change direction (L) --- \n "); - } - else { //target distance does not reach the limit - step.runAbs (posNow + stepsToGo); //move by (remaining) distance to reach target length - while(step.getState() != 1) vTaskDelay(1); //wait for move to finish - ESP_LOGD(TAG, "moving to %d\n", posNow+stepsToGo); - posNow += stepsToGo; - stepsToGo = 0; //finished, reset target length (could as well exit loop/break) - } - } - - //--- currently moving left --- - else { - remaining = posNow - POS_MIN_STEPS; - if (stepsToGo > remaining){ - step.runAbs (POS_MIN_STEPS); - while(step.getState() != 1) vTaskDelay(2); //wait for move to finish - posNow = POS_MIN_STEPS; - stepp_direction = true; - stepsToGo = stepsToGo - remaining; - ESP_LOGI(TAG, " --- moved to min -> change direction (R) --- \n "); - } - else { - step.runAbs (posNow - stepsToGo); //when moving left the coordinate has to be decreased - while(step.getState() != 1) vTaskDelay(2); //wait for move to finish - ESP_LOGD(TAG, "moving to %d\n", posNow - stepsToGo); - posNow -= stepsToGo; - stepsToGo = 0; - } - } - } - if(stepsTarget < 0) stepp_direction = !stepp_direction; //undo inversion of stepp_direction after reverse mode is finished - return; -} - - -//move axis certain Mm (relative) between left and right or reverse when negative -void travelMm(int length){ - travelSteps(length * STEPPER_STEPS_PER_MM); -} - - -//define zero/start position -//currently crashes into hardware limitation for certain time -//TODO: limit switch -void home() { - ESP_LOGW(TAG, "auto-home..."); - step.setSpeedMm(100, 500, 10); - step.runInf(1); - vTaskDelay(1500 / portTICK_PERIOD_MS); - step.stop(); - step.resetAbsolute(); - ESP_LOGW(TAG, "auto-home finished"); -} +////move axis certain Steps (relative) between left and right or reverse when negative +//void travelSteps(int stepsTarget){ +// //posNow = step.getPositionMm(); //not otherwise controlled, so no update necessary +// int stepsToGo, remaining; +// +// stepsToGo = abs(stepsTarget); +// if(stepsTarget < 0) stepp_direction = !stepp_direction; //invert direction in reverse mode +// +// while (stepsToGo != 0){ +// //--- currently moving right --- +// if (stepp_direction == true){ //currently moving right +// remaining = POS_MAX_STEPS - posNow; //calc remaining distance fom current position to limit +// if (stepsToGo > remaining){ //new distance will exceed limit +// //....step.runAbs (POS_MAX_STEPS); //move to limit +// //....while(step.getState() != 1) vTaskDelay(1); //wait for move to finish +// posNow = POS_MAX_STEPS; +// stepp_direction = false; //change current direction for next iteration +// stepsToGo = stepsToGo - remaining; //decrease target length by already traveled distance +// ESP_LOGI(TAG, " --- moved to max -> change direction (L) --- \n "); +// } +// else { //target distance does not reach the limit +// //....step.runAbs (posNow + stepsToGo); //move by (remaining) distance to reach target length +// //....while(step.getState() != 1) vTaskDelay(1); //wait for move to finish +// ESP_LOGD(TAG, "moving to %d\n", posNow+stepsToGo); +// posNow += stepsToGo; +// stepsToGo = 0; //finished, reset target length (could as well exit loop/break) +// } +// } +// +// //--- currently moving left --- +// else { +// remaining = posNow - POS_MIN_STEPS; +// if (stepsToGo > remaining){ +// //....step.runAbs (POS_MIN_STEPS); +// //....while(step.getState() != 1) vTaskDelay(2); //wait for move to finish +// posNow = POS_MIN_STEPS; +// stepp_direction = true; +// stepsToGo = stepsToGo - remaining; +// ESP_LOGI(TAG, " --- moved to min -> change direction (R) --- \n "); +// } +// else { +// //....step.runAbs (posNow - stepsToGo); //when moving left the coordinate has to be decreased +// while(step.getState() != 1) vTaskDelay(2); //wait for move to finish +// ESP_LOGD(TAG, "moving to %d\n", posNow - stepsToGo); +// posNow -= stepsToGo; +// stepsToGo = 0; +// } +// } +// } +// if(stepsTarget < 0) stepp_direction = !stepp_direction; //undo inversion of stepp_direction after reverse mode is finished +// return; +//} +// +// +////move axis certain Mm (relative) between left and right or reverse when negative +//void travelMm(int length){ +// travelSteps(length * STEPPER_STEPS_PER_MM); +//} +// +// +////define zero/start position +////currently crashes into hardware limitation for certain time +////TODO: limit switch +//void home() { +// ESP_LOGW(TAG, "auto-home..."); +// //....step.setSpeedMm(100, 500, 10); +// //....step.runInf(1); +// vTaskDelay(1500 / portTICK_PERIOD_MS); +// //....step.stop(); +// //....step.resetAbsolute(); +// ESP_LOGW(TAG, "auto-home finished"); +//} //initialize/configure stepper instance void init_stepper() { - ESP_LOGW(TAG, "initializing stepper..."); - DendoStepper_config_t step_cfg = { - .stepPin = STEPPER_STEP_PIN, - .dirPin = STEPPER_DIR_PIN, - .enPin = STEPPER_EN_PIN, - .timer_group = TIMER_GROUP_0, - .timer_idx = TIMER_0, - .miStep = MICROSTEP_32, - .stepAngle = 1.8}; - step.config(&step_cfg); - step.init(); +// ESP_LOGW(TAG, "initializing stepper..."); +// DendoStepper_config_t step_cfg = { +// .stepPin = STEPPER_STEP_PIN, +// .dirPin = STEPPER_DIR_PIN, +// .enPin = STEPPER_EN_PIN, +// .timer_group = TIMER_GROUP_0, +// .timer_idx = TIMER_0, +// .miStep = MICROSTEP_32, +// .stepAngle = 1.8}; +// //....step.config(&step_cfg); +// //....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 - step.setStepsPerMm(STEPPER_STEPS_PER_MM); //guide: 4mm/rot + stepper_init(); } @@ -155,7 +156,7 @@ void updateSpeedFromAdc() { int potiRead = gpio_readAdc(ADC_CHANNEL_POTI); //0-4095 GPIO34 double poti = potiRead/4095.0; 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); } @@ -166,80 +167,99 @@ void updateSpeedFromAdc() { //---------------------------- void task_stepper_test(void *pvParameter) { - init_stepper(); - home(); + stepper_init(); + while(1){ + vTaskDelay(20 / portTICK_PERIOD_MS); - while (1) { - updateSpeedFromAdc(); - step.runPosMm(STEPPER_TEST_TRAVEL); - while(step.getState() != 1) vTaskDelay(2); - ESP_LOGI(TAG, "finished moving right => moving left"); + //------ 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(); - updateSpeedFromAdc(); - step.runPosMm(-STEPPER_TEST_TRAVEL); - while(step.getState() != 1) vTaskDelay(2); //1=idle - ESP_LOGI(TAG, "finished moving left => moving right"); - } + if (SW_RESET.risingEdge) { + stepper_toggleDirection(); + buzzer.beep(1, 1000, 100); + } + 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 ----- //---------------------------- void task_stepper_ctl(void *pvParameter) { - //variables - int encStepsNow = 0; //get curret steps of encoder - int encStepsPrev = 0; //steps at last check - int encStepsDelta = 0; //steps changed since last iteration - - double cableLen = 0; - double travelStepsExact = 0; //steps axis has to travel - double travelStepsPartial = 0; - int travelStepsFull = 0; - double travelMm = 0; - double turns = 0; - - float potiModifier; - - init_stepper(); - home(); - - while(1){ - //get current length - encStepsNow = encoder_getSteps(); - - //calculate change - 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 - potiModifier = (float) gpio_readAdc(ADC_CHANNEL_POTI) / 4095; //0-4095 -> 0-1 - //ESP_LOGI(TAG, "current poti-modifier = %f", potiModifier); - - //calculate steps to move - cableLen = (double)encStepsDelta * 1000 / ENCODER_STEPS_PER_METER; - turns = cableLen / (PI * D_REEL); - travelMm = turns * D_CABLE; - travelStepsExact = travelMm * STEPPER_STEPS_PER_MM + travelStepsPartial; //convert mm to steps and add not moved partial steps - travelStepsPartial = 0; - travelStepsFull = (int)travelStepsExact; - - //move axis when ready to move at least 1 step - if (abs(travelStepsFull) > 1){ - 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_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(35, 100, 50); - //testing: get speed from poti - //step.setSpeedMm(35, 1000*potiModifier+1, 1000*potiModifier+1); - travelSteps(travelStepsExact); - encStepsPrev = encStepsNow; //update previous length - } - else { - //TODO use encoder queue to only run this check at encoder event? - vTaskDelay(2); - } - } +// //variables +// int encStepsNow = 0; //get curret steps of encoder +// int encStepsPrev = 0; //steps at last check +// int encStepsDelta = 0; //steps changed since last iteration +// +// double cableLen = 0; +// double travelStepsExact = 0; //steps axis has to travel +// double travelStepsPartial = 0; +// int travelStepsFull = 0; +// double travelMm = 0; +// double turns = 0; +// +// float potiModifier; +// +// init_stepper(); +// home(); +// +// while(1){ +// //get current length +// encStepsNow = encoder_getSteps(); +// +// //calculate change +// 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 +// potiModifier = (float) gpio_readAdc(ADC_CHANNEL_POTI) / 4095; //0-4095 -> 0-1 +// //ESP_LOGI(TAG, "current poti-modifier = %f", potiModifier); +// +// //calculate steps to move +// cableLen = (double)encStepsDelta * 1000 / ENCODER_STEPS_PER_METER; +// turns = cableLen / (PI * D_REEL); +// travelMm = turns * D_CABLE; +// travelStepsExact = travelMm * STEPPER_STEPS_PER_MM + travelStepsPartial; //convert mm to steps and add not moved partial steps +// travelStepsPartial = 0; +// travelStepsFull = (int)travelStepsExact; +// +// //move axis when ready to move at least 1 step +// if (abs(travelStepsFull) > 1){ +// 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_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(35, 100, 50); +// //testing: get speed from poti +// //step.setSpeedMm(35, 1000*potiModifier+1, 1000*potiModifier+1); +// travelSteps(travelStepsExact); +// encStepsPrev = encStepsNow; //update previous length +// } +// else { +// //TODO use encoder queue to only run this check at encoder event? +// vTaskDelay(2); +// } +// } } diff --git a/main/main.cpp b/main/main.cpp index 7872214..0533bd5 100644 --- a/main/main.cpp +++ b/main/main.cpp @@ -97,12 +97,12 @@ extern "C" void app_main() //create task for controlling the machine 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); +#endif //create task for handling the buzzer xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL); -#endif //beep at startup buzzer.beep(3, 70, 50); diff --git a/main/stepper.cpp b/main/stepper.cpp new file mode 100644 index 0000000..9c4b54a --- /dev/null +++ b/main/stepper.cpp @@ -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; +} + + diff --git a/main/stepper.hpp b/main/stepper.hpp new file mode 100644 index 0000000..4e9292d --- /dev/null +++ b/main/stepper.hpp @@ -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; +