Merge branch 'dev' - cable-guide functional
17
.gitignore
vendored
@ -1,12 +1,29 @@
|
||||
# ESP-IDF default build directory
|
||||
build
|
||||
sdkconfig.old
|
||||
dependencies.lock
|
||||
|
||||
# VIM files
|
||||
*.swp
|
||||
*.swo
|
||||
**/.cache
|
||||
|
||||
# VS-code
|
||||
settings.json
|
||||
|
||||
# drawio files
|
||||
*.bkp
|
||||
|
||||
# freecad backup files
|
||||
*.FCStd1
|
||||
*.FCBak
|
||||
# stl files are usually temporary
|
||||
*.stl
|
||||
|
||||
# kicad backup files
|
||||
pcb/*/*backups/
|
||||
|
||||
# other
|
||||
octave-workspace
|
||||
del
|
||||
screenshots
|
||||
|
@ -6,4 +6,4 @@ cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
#set(EXTRA_COMPONENT_DIRS ../esp-idf-lib/components)
|
||||
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
|
||||
project(cable-length-cutting)
|
||||
project(cable-length-cutter)
|
||||
|
127
README.md
@ -1,69 +1,94 @@
|
||||
# Links
|
||||
## connection plan
|
||||
See [connection-plan.drawio.pdf](connection-plan.drawio.pdf)
|
||||
# Overview
|
||||
Firmware and documentation of a custom built machine that winds and cuts cable to certain lengths.
|
||||
Extensive details about this project can be found on the website: [pfusch.zone/cable-length-cutter](https://pfusch.zone/cable-length-cutter)
|
||||
|
||||
<img src="img/cable-length-cutter.jpg" alt="Photo machine" style="width:60%;">
|
||||
|
||||
Photo of the built machine
|
||||
|
||||
## Current Features
|
||||
- Measure length using rotary encoder
|
||||
- Wind to set length while start-button is pressed
|
||||
- Automatic wire cutter
|
||||
- Control interface:
|
||||
- 2x 7-Segment display showing lengths and notifications
|
||||
- Buzzer for acoustic notifications
|
||||
- 4 Buttons and Potentiometer for setting the target length
|
||||
- Reset and Cut Button
|
||||
- Stepper motor controlling a linear axis guiding the cable while winding
|
||||
- Store last axis position at shutdown
|
||||
|
||||
|
||||
# Usage
|
||||

|
||||
|
||||
|
||||
# Electrical Details
|
||||
For detailed documentation of all electrical aspects, see [connection-plan.pdf](connection-plan.pdf).
|
||||
|
||||
|
||||
# Printed Parts
|
||||
All designed and 3D-printed parts can be found in the [cad/](cad/) folder. These parts were designed using FreeCAD.
|
||||
|
||||
|
||||
# Components
|
||||
### Custom pcb with ESP-32 microcontroller
|
||||
See [connection-plan.pdf](connection-plan.pdf)
|
||||
|
||||
### Rotary encoder LPD3806-600BM-G5-24C
|
||||
```
|
||||
- Pulses: 600 p/r (Single-phase 600 pulses /R,Two phase 4 frequency doubling to 2400 pulses)
|
||||
- Power source: DC5-24V
|
||||
- Shaft: 6*13mm/0.23*0.51"
|
||||
- Size: 38*35.5mm/1.49*1.39"
|
||||
- Output :AB 2phase output rectangular orthogonal pulse circuit, the output for the NPN open collector output type
|
||||
- Maximum mechanical speed: 5000 R / min
|
||||
- Response frequency: 0-20KHz
|
||||
- Cable length: 1.5 meter
|
||||
- size: http://domoticx.com/wp-content/uploads/2020/05/LPD3806-afmetingen.jpg
|
||||
- Wires: Green = A phase, white = B phase, red = Vcc power +, black = V0
|
||||
```
|
||||
### Variable Frequency Drive T13-400W-12-H
|
||||
See [docs/vfd/](docs/vfd/)
|
||||
|
||||
### Stepper-driver TB6600
|
||||
See [docs/stepper-driver_TB6600-Manual.pdf](docs/stepper-driver_TB6600-Manual.pdf)
|
||||
|
||||
### Linear Axis with Nema-12 28HB40 Stepper
|
||||
See [connection-plan.pdf](connection-plan.pdf)
|
||||
|
||||
## flowchart firmware
|
||||
See [function-diagram.drawio.pdf](function-diagram.drawio.pdf)
|
||||
|
||||
|
||||
|
||||
# Installation
|
||||
### Install esp-idf
|
||||
Currently using ESP-IDF **v4.4.4-148** (5.x did not work due to breaking changes and CMAKE issues)
|
||||
1. download esp-idf:
|
||||
```
|
||||
clone the esp-idf repository from github to /opt
|
||||
```
|
||||
2. checkout version needed:
|
||||
```
|
||||
git checkout release/4.4
|
||||
```
|
||||
3. run install script e.g.
|
||||
```
|
||||
For this project **ESP-IDF v4.4.4** is required (with other versions it might not compile)
|
||||
```bash
|
||||
#download esp-idf
|
||||
yay -S esp-idf
|
||||
#alternatively clone the esp-idf repository from github and do `git checkout release/4.4`
|
||||
|
||||
#run installation script in installed folder
|
||||
/opt/esp-idf/install.sh
|
||||
```
|
||||
|
||||
### Clone this repo
|
||||
```
|
||||
git clone git@github.com:Jonny999999/cable-length-cutter.git
|
||||
```
|
||||
|
||||
|
||||
|
||||
# Compilation
|
||||
# Build
|
||||
### Set up environment
|
||||
```bash
|
||||
source /opt/esp-idf/export.sh
|
||||
```
|
||||
(run once in terminal)
|
||||
(run once per terminal)
|
||||
|
||||
### Compile
|
||||
```bash
|
||||
cd board_single
|
||||
idf.py build
|
||||
#or
|
||||
idf.py build flash monitor
|
||||
```
|
||||
|
||||
|
||||
|
||||
|
||||
# Usage
|
||||
[WIP...]
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
# Components
|
||||
## rotary encoder LPD3806-600BM-G5-24C
|
||||
- Pulses: 600 p/r (Single-phase 600 pulses /R,Two phase 4 frequency doubling to 2400 pulses)
|
||||
- Power source: DC5-24V
|
||||
- Shaft: 6*13mm/0.23*0.51"
|
||||
- Size: 38*35.5mm/1.49*1.39"
|
||||
- Output :AB 2phase output rectangular orthogonal pulse circuit, the output for the NPN open collector output type
|
||||
- Maximum mechanical speed: 5000 R / min
|
||||
- Response frequency: 0-20KHz
|
||||
- Cable length: 1.5 meter
|
||||
- size: http://domoticx.com/wp-content/uploads/2020/05/LPD3806-afmetingen.jpg
|
||||
- Wires: Green = A phase, white = B phase, red = Vcc power +, black = V0
|
||||
|
||||
# Flash
|
||||
- connect FTDI programmer to board (VCC to VCC; TX to RX; RX to TX)
|
||||
- press REST and BOOT button
|
||||
- release RESET button (keep pressing boot)
|
||||
- run flash command:
|
||||
```bash
|
||||
idf.py flash
|
||||
```
|
BIN
cad/cnc-guide/axis-mount.stl
Normal file
BIN
cad/cnc-guide/axis_mounts.FCStd
Normal file
BIN
cad/reel/cable-reel_v2.2.2.FCStd
Normal file
BIN
cad/reel/cable-reel_v2.2.FCStd
Normal file
1
components/DendoStepper/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
||||
idf_component_register(SRCS DendoStepper.cpp INCLUDE_DIRS include)
|
413
components/DendoStepper/DendoStepper.cpp
Normal file
@ -0,0 +1,413 @@
|
||||
#include "DendoStepper.h"
|
||||
#include "esp_log.h"
|
||||
|
||||
#define STEP_DEBUG
|
||||
|
||||
#ifdef STEP_DEBUG
|
||||
#define STEP_LOGI(...) ESP_LOGI(__VA_ARGS__)
|
||||
#define STEP_LOGW(...) ESP_LOGW(__VA_ARGS__)
|
||||
#define STEP_LOGE(...) ESP_LOGE(__VA_ARGS__)
|
||||
#else
|
||||
#define STEP_LOGI(...) while (0)
|
||||
#define STEP_LOGW(...) while (0)
|
||||
#define STEP_LOGE(...) ESP_LOGE(__VA_ARGS__)
|
||||
#endif
|
||||
|
||||
bool state = 0;
|
||||
|
||||
// PUBLIC definitions
|
||||
|
||||
DendoStepper::DendoStepper()
|
||||
{
|
||||
}
|
||||
|
||||
void DendoStepper::config(DendoStepper_config_t *config)
|
||||
{
|
||||
memcpy(&conf, config, sizeof(conf));
|
||||
}
|
||||
|
||||
void DendoStepper::disableMotor()
|
||||
{
|
||||
setEn(true);
|
||||
STEP_LOGI("DendoStepper", "Disabled");
|
||||
ctrl.status = DISABLED;
|
||||
}
|
||||
|
||||
void DendoStepper::enableMotor()
|
||||
{
|
||||
setEn(false);
|
||||
ctrl.status = IDLE;
|
||||
STEP_LOGI("DendoStepper", "Enabled");
|
||||
timerStarted = 0;
|
||||
}
|
||||
|
||||
void DendoStepper::init(uint8_t stepP, uint8_t dirP, uint8_t enP, timer_group_t group, timer_idx_t index, microStepping_t microstepping = MICROSTEP_1, uint16_t stepsPerRot = 200)
|
||||
{
|
||||
conf.stepPin = stepP;
|
||||
conf.dirPin = dirP;
|
||||
conf.enPin = enP;
|
||||
conf.timer_group = group;
|
||||
conf.timer_idx = index;
|
||||
conf.miStep = microstepping;
|
||||
ctrl.status = 0;
|
||||
init();
|
||||
}
|
||||
|
||||
void DendoStepper::init()
|
||||
{
|
||||
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
|
||||
.pin_bit_mask = mask,
|
||||
.mode = GPIO_MODE_OUTPUT,
|
||||
.pull_up_en = GPIO_PULLUP_DISABLE,
|
||||
.pull_down_en = GPIO_PULLDOWN_DISABLE,
|
||||
.intr_type = GPIO_INTR_DISABLE,
|
||||
};
|
||||
// set the gpios as per gpio_conf
|
||||
ESP_ERROR_CHECK(gpio_config(&gpio_conf));
|
||||
|
||||
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
|
||||
};
|
||||
|
||||
// calculate stepsPerRot
|
||||
ctrl.stepsPerRot = (360.0 / conf.stepAngle) * conf.miStep;
|
||||
|
||||
STEP_LOGI("DendoStepper", "Steps per one rotation:%d", ctrl.stepsPerRot);
|
||||
|
||||
if (conf.timer_group != TIMER_GROUP_MAX && conf.timer_idx != TIMER_MAX)
|
||||
{
|
||||
// timer was configured explixitly in config structure, we dont need to do it here
|
||||
goto timer_avail;
|
||||
}
|
||||
|
||||
// try to find free timer
|
||||
timer_config_t temp;
|
||||
for (int i = 0; i < 1; i++)
|
||||
{
|
||||
for (int j = 0; j < 1; j++)
|
||||
{
|
||||
timer_get_config((timer_group_t)i, (timer_idx_t)j, &temp);
|
||||
if (temp.alarm_en == TIMER_ALARM_DIS)
|
||||
{
|
||||
// if the alarm is disabled, chances are no other dendostepper instance is using it
|
||||
conf.timer_group = (timer_group_t)i;
|
||||
conf.timer_idx = (timer_idx_t)j;
|
||||
goto timer_avail;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// if we got here it means that there isnt any free timer available
|
||||
STEP_LOGE("DendoStepper", "No free timer available, this stepper wont work");
|
||||
return;
|
||||
|
||||
timer_avail:
|
||||
ESP_ERROR_CHECK(timer_init(conf.timer_group, conf.timer_idx, &timer_conf)); // init the timer
|
||||
ESP_ERROR_CHECK(timer_set_counter_value(conf.timer_group, conf.timer_idx, 0)); // set it to 0
|
||||
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();
|
||||
|
||||
if (!relative) // why would u call it with 0 wtf
|
||||
return ESP_ERR_NOT_SUPPORTED;
|
||||
|
||||
if (ctrl.status > IDLE) { //currently moving
|
||||
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
|
||||
ctrl.status = ACC;
|
||||
setDir(relative < 0); // set CCW if <0, else set CW
|
||||
calc(abs(relative)); // calculate velocity profile
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
esp_err_t DendoStepper::runPosMm(int32_t relative)
|
||||
{
|
||||
if (ctrl.stepsPerMm == 0)
|
||||
{
|
||||
STEP_LOGE("DendoStepper", "Steps per millimeter not set, cannot move!");
|
||||
}
|
||||
return runPos(relative * ctrl.stepsPerMm);
|
||||
}
|
||||
|
||||
esp_err_t DendoStepper::runAbs(uint32_t 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;
|
||||
|
||||
int32_t relativeSteps = 0;
|
||||
relativeSteps = (int32_t)position - currentPos;
|
||||
|
||||
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)
|
||||
{
|
||||
STEP_LOGE("DendoStepper", "Steps per millimeter not set, cannot move!");
|
||||
}
|
||||
return runAbs(position * ctrl.stepsPerMm);
|
||||
}
|
||||
|
||||
void DendoStepper::setSpeed(uint32_t speed, uint16_t accT, uint16_t decT)
|
||||
{
|
||||
ctrl.speed = speed;
|
||||
ctrl.acc = ctrl.speed / (accT / 4000.0);
|
||||
ctrl.dec = ctrl.speed / (decT / 4000.0);
|
||||
STEP_LOGI("DendoStepper", "Speed set: %d steps/s t+=%d s t-=%d s", speed, accT, decT);
|
||||
}
|
||||
|
||||
void DendoStepper::setSpeedMm(uint32_t speed, uint16_t accT, uint16_t decT)
|
||||
{
|
||||
if (ctrl.stepsPerMm == 0)
|
||||
{
|
||||
STEP_LOGE("DendoStepper", "Steps per millimeter not set, cannot set the speed!");
|
||||
}
|
||||
ctrl.speed = speed * ctrl.stepsPerMm;
|
||||
|
||||
ctrl.acc = ctrl.speed / (accT / 4000.0);
|
||||
ctrl.dec = ctrl.speed / (decT / 4000.0);
|
||||
STEP_LOGI("DendoStepper", "Speed set: v=%d mm/s t+=%d s t-=%d s", speed, accT, decT);
|
||||
}
|
||||
|
||||
//CUSTOM - change speed while running
|
||||
//FIXME: this approach does not work, since calc function would have to be run after change, this will mess up target steps...
|
||||
//void DendoStepper::changeSpeed(uint32_t speed)
|
||||
//{
|
||||
// //TODO reduce duplicate code (e.g. call setSpeed function)
|
||||
// //change speed
|
||||
// ctrl.speed = speed;
|
||||
// //change status to ACC/DEC
|
||||
// STEP_LOGI("DendoStepper", "Speed changed: from v=%.2f rad/s to v=%.2f rad/s", ctrl.speed, speed);
|
||||
// if (speed > ctrl.speed) ctrl.status = ACC;
|
||||
// if (speed < ctrl.speed) ctrl.status = DEC;
|
||||
//}
|
||||
//
|
||||
//void DendoStepper::changeSpeedMm(uint32_t speed)
|
||||
//{
|
||||
// //TODO reduce duplicate code (e.g. call setSpeedMm function)
|
||||
// if (ctrl.stepsPerMm == 0)
|
||||
// {
|
||||
// STEP_LOGE("DendoStepper", "Steps per millimeter not set, cannot set the speed!");
|
||||
// }
|
||||
// //calc new speed
|
||||
// float speedNew = speed * ctrl.stepsPerMm;
|
||||
// //change status to ACC/DEC
|
||||
// if (speedNew > ctl.speed) ctrl.status = ACC;
|
||||
// if (speedNew < ctl.speed) ctrl.status = DEC;
|
||||
// //update speed, log output
|
||||
// ctrl.speed = speedNew;
|
||||
// STEP_LOGI("DendoStepper", "Speed changed: from v=%.2f rad/s to v=%.2f rad/s", ctrl.speed, speedNew);
|
||||
//}
|
||||
|
||||
|
||||
void DendoStepper::setStepsPerMm(uint16_t steps)
|
||||
{
|
||||
ctrl.stepsPerMm = steps;
|
||||
}
|
||||
|
||||
uint16_t DendoStepper::getStepsPerMm()
|
||||
{
|
||||
return ctrl.stepsPerMm;
|
||||
}
|
||||
|
||||
uint8_t DendoStepper::getState()
|
||||
{
|
||||
return ctrl.status;
|
||||
}
|
||||
|
||||
uint64_t DendoStepper::getPosition()
|
||||
{
|
||||
return currentPos;
|
||||
}
|
||||
|
||||
uint64_t DendoStepper::getPositionMm()
|
||||
{
|
||||
return getPosition() / ctrl.stepsPerMm;
|
||||
}
|
||||
|
||||
void DendoStepper::resetAbsolute()
|
||||
{
|
||||
currentPos = 0;
|
||||
}
|
||||
|
||||
void DendoStepper::runInf(bool direction)
|
||||
{
|
||||
if (ctrl.status > IDLE)
|
||||
{
|
||||
STEP_LOGE("DendoStepper", "Motor is moving, this command will be ignored");
|
||||
return;
|
||||
}
|
||||
if (ctrl.status == DISABLED)
|
||||
{
|
||||
enableMotor();
|
||||
}
|
||||
ctrl.runInfinite = true;
|
||||
setDir(direction);
|
||||
calc(UINT32_MAX);
|
||||
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
|
||||
}
|
||||
|
||||
uint16_t DendoStepper::getSpeed()
|
||||
{
|
||||
return ctrl.speed;
|
||||
}
|
||||
|
||||
float DendoStepper::getAcc()
|
||||
{
|
||||
return ctrl.acc;
|
||||
}
|
||||
|
||||
void DendoStepper::stop()
|
||||
{
|
||||
if (ctrl.status <= IDLE)
|
||||
{
|
||||
return;
|
||||
}
|
||||
ctrl.runInfinite = false;
|
||||
timer_pause(conf.timer_group, conf.timer_idx); // stop the timer
|
||||
ctrl.statusPrev = ctrl.status; //update previous status
|
||||
ctrl.status = IDLE;
|
||||
ctrl.stepCnt = 0;
|
||||
gpio_set_level((gpio_num_t)conf.stepPin, 0);
|
||||
}
|
||||
|
||||
// PRIVATE definitions
|
||||
|
||||
void DendoStepper::setEn(bool state)
|
||||
{
|
||||
ESP_ERROR_CHECK(gpio_set_level((gpio_num_t)conf.enPin, state));
|
||||
}
|
||||
|
||||
void DendoStepper::setDir(bool state)
|
||||
{
|
||||
ctrl.dir = state;
|
||||
ESP_ERROR_CHECK(gpio_set_level((gpio_num_t)conf.dirPin, state));
|
||||
}
|
||||
|
||||
/* Timer callback, used for generating pulses and calculating speed profile in real time */
|
||||
bool DendoStepper::xISR()
|
||||
{
|
||||
GPIO.out_w1ts = (1ULL << conf.stepPin);
|
||||
// add and substract one step
|
||||
|
||||
ctrl.stepCnt++;
|
||||
|
||||
//CUSTOM: track actual precice current position
|
||||
if (ctrl.dir) {
|
||||
ctrl.posActual ++;
|
||||
} else {
|
||||
ctrl.posActual --;
|
||||
}
|
||||
//CUSTOM: track remaining steps for eventually resuming
|
||||
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.status = IDLE;
|
||||
ctrl.stepCnt = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (ctrl.stepCnt > 0 && ctrl.stepCnt < ctrl.accEnd)
|
||||
{ // we are accelerating
|
||||
ctrl.currentSpeed += ctrl.accInc;
|
||||
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.status = DEC; // we are deccelerating
|
||||
}
|
||||
else
|
||||
{
|
||||
ctrl.currentSpeed = ctrl.targetSpeed;
|
||||
ctrl.statusPrev = ctrl.status; //update previous status
|
||||
ctrl.status = COAST; // we are coasting
|
||||
}
|
||||
|
||||
ctrl.stepInterval = TIMER_F / ctrl.currentSpeed;
|
||||
// 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)
|
||||
{
|
||||
//steps from ctrl.speed -> 0:
|
||||
ctrl.decSteps = 0.5 * ctrl.dec * (ctrl.speed / ctrl.dec) * (ctrl.speed / ctrl.dec);
|
||||
//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;
|
||||
|
||||
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.decSteps = 0.5 * ctrl.dec * (ctrl.speed / ctrl.dec) * (ctrl.speed / ctrl.dec);
|
||||
}
|
||||
|
||||
ctrl.accEnd = ctrl.accSteps;
|
||||
ctrl.coastEnd = targetSteps - ctrl.decSteps;
|
||||
ctrl.targetSpeed = ctrl.speed;
|
||||
|
||||
ctrl.accInc = ctrl.targetSpeed / (double)ctrl.accSteps;
|
||||
ctrl.decInc = ctrl.targetSpeed / (double)ctrl.decSteps;
|
||||
|
||||
ctrl.currentSpeed = ctrl.accInc;
|
||||
|
||||
ctrl.stepInterval = TIMER_F / ctrl.currentSpeed;
|
||||
ctrl.stepsToGo = targetSteps;
|
||||
|
||||
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);
|
||||
}
|
674
components/DendoStepper/LICENSE
Normal file
@ -0,0 +1,674 @@
|
||||
GNU GENERAL PUBLIC LICENSE
|
||||
Version 3, 29 June 2007
|
||||
|
||||
Copyright (C) 2007 Free Software Foundation, Inc. <https://fsf.org/>
|
||||
Everyone is permitted to copy and distribute verbatim copies
|
||||
of this license document, but changing it is not allowed.
|
||||
|
||||
Preamble
|
||||
|
||||
The GNU General Public License is a free, copyleft license for
|
||||
software and other kinds of works.
|
||||
|
||||
The licenses for most software and other practical works are designed
|
||||
to take away your freedom to share and change the works. By contrast,
|
||||
the GNU General Public License is intended to guarantee your freedom to
|
||||
share and change all versions of a program--to make sure it remains free
|
||||
software for all its users. We, the Free Software Foundation, use the
|
||||
GNU General Public License for most of our software; it applies also to
|
||||
any other work released this way by its authors. You can apply it to
|
||||
your programs, too.
|
||||
|
||||
When we speak of free software, we are referring to freedom, not
|
||||
price. Our General Public Licenses are designed to make sure that you
|
||||
have the freedom to distribute copies of free software (and charge for
|
||||
them if you wish), that you receive source code or can get it if you
|
||||
want it, that you can change the software or use pieces of it in new
|
||||
free programs, and that you know you can do these things.
|
||||
|
||||
To protect your rights, we need to prevent others from denying you
|
||||
these rights or asking you to surrender the rights. Therefore, you have
|
||||
certain responsibilities if you distribute copies of the software, or if
|
||||
you modify it: responsibilities to respect the freedom of others.
|
||||
|
||||
For example, if you distribute copies of such a program, whether
|
||||
gratis or for a fee, you must pass on to the recipients the same
|
||||
freedoms that you received. You must make sure that they, too, receive
|
||||
or can get the source code. And you must show them these terms so they
|
||||
know their rights.
|
||||
|
||||
Developers that use the GNU GPL protect your rights with two steps:
|
||||
(1) assert copyright on the software, and (2) offer you this License
|
||||
giving you legal permission to copy, distribute and/or modify it.
|
||||
|
||||
For the developers' and authors' protection, the GPL clearly explains
|
||||
that there is no warranty for this free software. For both users' and
|
||||
authors' sake, the GPL requires that modified versions be marked as
|
||||
changed, so that their problems will not be attributed erroneously to
|
||||
authors of previous versions.
|
||||
|
||||
Some devices are designed to deny users access to install or run
|
||||
modified versions of the software inside them, although the manufacturer
|
||||
can do so. This is fundamentally incompatible with the aim of
|
||||
protecting users' freedom to change the software. The systematic
|
||||
pattern of such abuse occurs in the area of products for individuals to
|
||||
use, which is precisely where it is most unacceptable. Therefore, we
|
||||
have designed this version of the GPL to prohibit the practice for those
|
||||
products. If such problems arise substantially in other domains, we
|
||||
stand ready to extend this provision to those domains in future versions
|
||||
of the GPL, as needed to protect the freedom of users.
|
||||
|
||||
Finally, every program is threatened constantly by software patents.
|
||||
States should not allow patents to restrict development and use of
|
||||
software on general-purpose computers, but in those that do, we wish to
|
||||
avoid the special danger that patents applied to a free program could
|
||||
make it effectively proprietary. To prevent this, the GPL assures that
|
||||
patents cannot be used to render the program non-free.
|
||||
|
||||
The precise terms and conditions for copying, distribution and
|
||||
modification follow.
|
||||
|
||||
TERMS AND CONDITIONS
|
||||
|
||||
0. Definitions.
|
||||
|
||||
"This License" refers to version 3 of the GNU General Public License.
|
||||
|
||||
"Copyright" also means copyright-like laws that apply to other kinds of
|
||||
works, such as semiconductor masks.
|
||||
|
||||
"The Program" refers to any copyrightable work licensed under this
|
||||
License. Each licensee is addressed as "you". "Licensees" and
|
||||
"recipients" may be individuals or organizations.
|
||||
|
||||
To "modify" a work means to copy from or adapt all or part of the work
|
||||
in a fashion requiring copyright permission, other than the making of an
|
||||
exact copy. The resulting work is called a "modified version" of the
|
||||
earlier work or a work "based on" the earlier work.
|
||||
|
||||
A "covered work" means either the unmodified Program or a work based
|
||||
on the Program.
|
||||
|
||||
To "propagate" a work means to do anything with it that, without
|
||||
permission, would make you directly or secondarily liable for
|
||||
infringement under applicable copyright law, except executing it on a
|
||||
computer or modifying a private copy. Propagation includes copying,
|
||||
distribution (with or without modification), making available to the
|
||||
public, and in some countries other activities as well.
|
||||
|
||||
To "convey" a work means any kind of propagation that enables other
|
||||
parties to make or receive copies. Mere interaction with a user through
|
||||
a computer network, with no transfer of a copy, is not conveying.
|
||||
|
||||
An interactive user interface displays "Appropriate Legal Notices"
|
||||
to the extent that it includes a convenient and prominently visible
|
||||
feature that (1) displays an appropriate copyright notice, and (2)
|
||||
tells the user that there is no warranty for the work (except to the
|
||||
extent that warranties are provided), that licensees may convey the
|
||||
work under this License, and how to view a copy of this License. If
|
||||
the interface presents a list of user commands or options, such as a
|
||||
menu, a prominent item in the list meets this criterion.
|
||||
|
||||
1. Source Code.
|
||||
|
||||
The "source code" for a work means the preferred form of the work
|
||||
for making modifications to it. "Object code" means any non-source
|
||||
form of a work.
|
||||
|
||||
A "Standard Interface" means an interface that either is an official
|
||||
standard defined by a recognized standards body, or, in the case of
|
||||
interfaces specified for a particular programming language, one that
|
||||
is widely used among developers working in that language.
|
||||
|
||||
The "System Libraries" of an executable work include anything, other
|
||||
than the work as a whole, that (a) is included in the normal form of
|
||||
packaging a Major Component, but which is not part of that Major
|
||||
Component, and (b) serves only to enable use of the work with that
|
||||
Major Component, or to implement a Standard Interface for which an
|
||||
implementation is available to the public in source code form. A
|
||||
"Major Component", in this context, means a major essential component
|
||||
(kernel, window system, and so on) of the specific operating system
|
||||
(if any) on which the executable work runs, or a compiler used to
|
||||
produce the work, or an object code interpreter used to run it.
|
||||
|
||||
The "Corresponding Source" for a work in object code form means all
|
||||
the source code needed to generate, install, and (for an executable
|
||||
work) run the object code and to modify the work, including scripts to
|
||||
control those activities. However, it does not include the work's
|
||||
System Libraries, or general-purpose tools or generally available free
|
||||
programs which are used unmodified in performing those activities but
|
||||
which are not part of the work. For example, Corresponding Source
|
||||
includes interface definition files associated with source files for
|
||||
the work, and the source code for shared libraries and dynamically
|
||||
linked subprograms that the work is specifically designed to require,
|
||||
such as by intimate data communication or control flow between those
|
||||
subprograms and other parts of the work.
|
||||
|
||||
The Corresponding Source need not include anything that users
|
||||
can regenerate automatically from other parts of the Corresponding
|
||||
Source.
|
||||
|
||||
The Corresponding Source for a work in source code form is that
|
||||
same work.
|
||||
|
||||
2. Basic Permissions.
|
||||
|
||||
All rights granted under this License are granted for the term of
|
||||
copyright on the Program, and are irrevocable provided the stated
|
||||
conditions are met. This License explicitly affirms your unlimited
|
||||
permission to run the unmodified Program. The output from running a
|
||||
covered work is covered by this License only if the output, given its
|
||||
content, constitutes a covered work. This License acknowledges your
|
||||
rights of fair use or other equivalent, as provided by copyright law.
|
||||
|
||||
You may make, run and propagate covered works that you do not
|
||||
convey, without conditions so long as your license otherwise remains
|
||||
in force. You may convey covered works to others for the sole purpose
|
||||
of having them make modifications exclusively for you, or provide you
|
||||
with facilities for running those works, provided that you comply with
|
||||
the terms of this License in conveying all material for which you do
|
||||
not control copyright. Those thus making or running the covered works
|
||||
for you must do so exclusively on your behalf, under your direction
|
||||
and control, on terms that prohibit them from making any copies of
|
||||
your copyrighted material outside their relationship with you.
|
||||
|
||||
Conveying under any other circumstances is permitted solely under
|
||||
the conditions stated below. Sublicensing is not allowed; section 10
|
||||
makes it unnecessary.
|
||||
|
||||
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
|
||||
|
||||
No covered work shall be deemed part of an effective technological
|
||||
measure under any applicable law fulfilling obligations under article
|
||||
11 of the WIPO copyright treaty adopted on 20 December 1996, or
|
||||
similar laws prohibiting or restricting circumvention of such
|
||||
measures.
|
||||
|
||||
When you convey a covered work, you waive any legal power to forbid
|
||||
circumvention of technological measures to the extent such circumvention
|
||||
is effected by exercising rights under this License with respect to
|
||||
the covered work, and you disclaim any intention to limit operation or
|
||||
modification of the work as a means of enforcing, against the work's
|
||||
users, your or third parties' legal rights to forbid circumvention of
|
||||
technological measures.
|
||||
|
||||
4. Conveying Verbatim Copies.
|
||||
|
||||
You may convey verbatim copies of the Program's source code as you
|
||||
receive it, in any medium, provided that you conspicuously and
|
||||
appropriately publish on each copy an appropriate copyright notice;
|
||||
keep intact all notices stating that this License and any
|
||||
non-permissive terms added in accord with section 7 apply to the code;
|
||||
keep intact all notices of the absence of any warranty; and give all
|
||||
recipients a copy of this License along with the Program.
|
||||
|
||||
You may charge any price or no price for each copy that you convey,
|
||||
and you may offer support or warranty protection for a fee.
|
||||
|
||||
5. Conveying Modified Source Versions.
|
||||
|
||||
You may convey a work based on the Program, or the modifications to
|
||||
produce it from the Program, in the form of source code under the
|
||||
terms of section 4, provided that you also meet all of these conditions:
|
||||
|
||||
a) The work must carry prominent notices stating that you modified
|
||||
it, and giving a relevant date.
|
||||
|
||||
b) The work must carry prominent notices stating that it is
|
||||
released under this License and any conditions added under section
|
||||
7. This requirement modifies the requirement in section 4 to
|
||||
"keep intact all notices".
|
||||
|
||||
c) You must license the entire work, as a whole, under this
|
||||
License to anyone who comes into possession of a copy. This
|
||||
License will therefore apply, along with any applicable section 7
|
||||
additional terms, to the whole of the work, and all its parts,
|
||||
regardless of how they are packaged. This License gives no
|
||||
permission to license the work in any other way, but it does not
|
||||
invalidate such permission if you have separately received it.
|
||||
|
||||
d) If the work has interactive user interfaces, each must display
|
||||
Appropriate Legal Notices; however, if the Program has interactive
|
||||
interfaces that do not display Appropriate Legal Notices, your
|
||||
work need not make them do so.
|
||||
|
||||
A compilation of a covered work with other separate and independent
|
||||
works, which are not by their nature extensions of the covered work,
|
||||
and which are not combined with it such as to form a larger program,
|
||||
in or on a volume of a storage or distribution medium, is called an
|
||||
"aggregate" if the compilation and its resulting copyright are not
|
||||
used to limit the access or legal rights of the compilation's users
|
||||
beyond what the individual works permit. Inclusion of a covered work
|
||||
in an aggregate does not cause this License to apply to the other
|
||||
parts of the aggregate.
|
||||
|
||||
6. Conveying Non-Source Forms.
|
||||
|
||||
You may convey a covered work in object code form under the terms
|
||||
of sections 4 and 5, provided that you also convey the
|
||||
machine-readable Corresponding Source under the terms of this License,
|
||||
in one of these ways:
|
||||
|
||||
a) Convey the object code in, or embodied in, a physical product
|
||||
(including a physical distribution medium), accompanied by the
|
||||
Corresponding Source fixed on a durable physical medium
|
||||
customarily used for software interchange.
|
||||
|
||||
b) Convey the object code in, or embodied in, a physical product
|
||||
(including a physical distribution medium), accompanied by a
|
||||
written offer, valid for at least three years and valid for as
|
||||
long as you offer spare parts or customer support for that product
|
||||
model, to give anyone who possesses the object code either (1) a
|
||||
copy of the Corresponding Source for all the software in the
|
||||
product that is covered by this License, on a durable physical
|
||||
medium customarily used for software interchange, for a price no
|
||||
more than your reasonable cost of physically performing this
|
||||
conveying of source, or (2) access to copy the
|
||||
Corresponding Source from a network server at no charge.
|
||||
|
||||
c) Convey individual copies of the object code with a copy of the
|
||||
written offer to provide the Corresponding Source. This
|
||||
alternative is allowed only occasionally and noncommercially, and
|
||||
only if you received the object code with such an offer, in accord
|
||||
with subsection 6b.
|
||||
|
||||
d) Convey the object code by offering access from a designated
|
||||
place (gratis or for a charge), and offer equivalent access to the
|
||||
Corresponding Source in the same way through the same place at no
|
||||
further charge. You need not require recipients to copy the
|
||||
Corresponding Source along with the object code. If the place to
|
||||
copy the object code is a network server, the Corresponding Source
|
||||
may be on a different server (operated by you or a third party)
|
||||
that supports equivalent copying facilities, provided you maintain
|
||||
clear directions next to the object code saying where to find the
|
||||
Corresponding Source. Regardless of what server hosts the
|
||||
Corresponding Source, you remain obligated to ensure that it is
|
||||
available for as long as needed to satisfy these requirements.
|
||||
|
||||
e) Convey the object code using peer-to-peer transmission, provided
|
||||
you inform other peers where the object code and Corresponding
|
||||
Source of the work are being offered to the general public at no
|
||||
charge under subsection 6d.
|
||||
|
||||
A separable portion of the object code, whose source code is excluded
|
||||
from the Corresponding Source as a System Library, need not be
|
||||
included in conveying the object code work.
|
||||
|
||||
A "User Product" is either (1) a "consumer product", which means any
|
||||
tangible personal property which is normally used for personal, family,
|
||||
or household purposes, or (2) anything designed or sold for incorporation
|
||||
into a dwelling. In determining whether a product is a consumer product,
|
||||
doubtful cases shall be resolved in favor of coverage. For a particular
|
||||
product received by a particular user, "normally used" refers to a
|
||||
typical or common use of that class of product, regardless of the status
|
||||
of the particular user or of the way in which the particular user
|
||||
actually uses, or expects or is expected to use, the product. A product
|
||||
is a consumer product regardless of whether the product has substantial
|
||||
commercial, industrial or non-consumer uses, unless such uses represent
|
||||
the only significant mode of use of the product.
|
||||
|
||||
"Installation Information" for a User Product means any methods,
|
||||
procedures, authorization keys, or other information required to install
|
||||
and execute modified versions of a covered work in that User Product from
|
||||
a modified version of its Corresponding Source. The information must
|
||||
suffice to ensure that the continued functioning of the modified object
|
||||
code is in no case prevented or interfered with solely because
|
||||
modification has been made.
|
||||
|
||||
If you convey an object code work under this section in, or with, or
|
||||
specifically for use in, a User Product, and the conveying occurs as
|
||||
part of a transaction in which the right of possession and use of the
|
||||
User Product is transferred to the recipient in perpetuity or for a
|
||||
fixed term (regardless of how the transaction is characterized), the
|
||||
Corresponding Source conveyed under this section must be accompanied
|
||||
by the Installation Information. But this requirement does not apply
|
||||
if neither you nor any third party retains the ability to install
|
||||
modified object code on the User Product (for example, the work has
|
||||
been installed in ROM).
|
||||
|
||||
The requirement to provide Installation Information does not include a
|
||||
requirement to continue to provide support service, warranty, or updates
|
||||
for a work that has been modified or installed by the recipient, or for
|
||||
the User Product in which it has been modified or installed. Access to a
|
||||
network may be denied when the modification itself materially and
|
||||
adversely affects the operation of the network or violates the rules and
|
||||
protocols for communication across the network.
|
||||
|
||||
Corresponding Source conveyed, and Installation Information provided,
|
||||
in accord with this section must be in a format that is publicly
|
||||
documented (and with an implementation available to the public in
|
||||
source code form), and must require no special password or key for
|
||||
unpacking, reading or copying.
|
||||
|
||||
7. Additional Terms.
|
||||
|
||||
"Additional permissions" are terms that supplement the terms of this
|
||||
License by making exceptions from one or more of its conditions.
|
||||
Additional permissions that are applicable to the entire Program shall
|
||||
be treated as though they were included in this License, to the extent
|
||||
that they are valid under applicable law. If additional permissions
|
||||
apply only to part of the Program, that part may be used separately
|
||||
under those permissions, but the entire Program remains governed by
|
||||
this License without regard to the additional permissions.
|
||||
|
||||
When you convey a copy of a covered work, you may at your option
|
||||
remove any additional permissions from that copy, or from any part of
|
||||
it. (Additional permissions may be written to require their own
|
||||
removal in certain cases when you modify the work.) You may place
|
||||
additional permissions on material, added by you to a covered work,
|
||||
for which you have or can give appropriate copyright permission.
|
||||
|
||||
Notwithstanding any other provision of this License, for material you
|
||||
add to a covered work, you may (if authorized by the copyright holders of
|
||||
that material) supplement the terms of this License with terms:
|
||||
|
||||
a) Disclaiming warranty or limiting liability differently from the
|
||||
terms of sections 15 and 16 of this License; or
|
||||
|
||||
b) Requiring preservation of specified reasonable legal notices or
|
||||
author attributions in that material or in the Appropriate Legal
|
||||
Notices displayed by works containing it; or
|
||||
|
||||
c) Prohibiting misrepresentation of the origin of that material, or
|
||||
requiring that modified versions of such material be marked in
|
||||
reasonable ways as different from the original version; or
|
||||
|
||||
d) Limiting the use for publicity purposes of names of licensors or
|
||||
authors of the material; or
|
||||
|
||||
e) Declining to grant rights under trademark law for use of some
|
||||
trade names, trademarks, or service marks; or
|
||||
|
||||
f) Requiring indemnification of licensors and authors of that
|
||||
material by anyone who conveys the material (or modified versions of
|
||||
it) with contractual assumptions of liability to the recipient, for
|
||||
any liability that these contractual assumptions directly impose on
|
||||
those licensors and authors.
|
||||
|
||||
All other non-permissive additional terms are considered "further
|
||||
restrictions" within the meaning of section 10. If the Program as you
|
||||
received it, or any part of it, contains a notice stating that it is
|
||||
governed by this License along with a term that is a further
|
||||
restriction, you may remove that term. If a license document contains
|
||||
a further restriction but permits relicensing or conveying under this
|
||||
License, you may add to a covered work material governed by the terms
|
||||
of that license document, provided that the further restriction does
|
||||
not survive such relicensing or conveying.
|
||||
|
||||
If you add terms to a covered work in accord with this section, you
|
||||
must place, in the relevant source files, a statement of the
|
||||
additional terms that apply to those files, or a notice indicating
|
||||
where to find the applicable terms.
|
||||
|
||||
Additional terms, permissive or non-permissive, may be stated in the
|
||||
form of a separately written license, or stated as exceptions;
|
||||
the above requirements apply either way.
|
||||
|
||||
8. Termination.
|
||||
|
||||
You may not propagate or modify a covered work except as expressly
|
||||
provided under this License. Any attempt otherwise to propagate or
|
||||
modify it is void, and will automatically terminate your rights under
|
||||
this License (including any patent licenses granted under the third
|
||||
paragraph of section 11).
|
||||
|
||||
However, if you cease all violation of this License, then your
|
||||
license from a particular copyright holder is reinstated (a)
|
||||
provisionally, unless and until the copyright holder explicitly and
|
||||
finally terminates your license, and (b) permanently, if the copyright
|
||||
holder fails to notify you of the violation by some reasonable means
|
||||
prior to 60 days after the cessation.
|
||||
|
||||
Moreover, your license from a particular copyright holder is
|
||||
reinstated permanently if the copyright holder notifies you of the
|
||||
violation by some reasonable means, this is the first time you have
|
||||
received notice of violation of this License (for any work) from that
|
||||
copyright holder, and you cure the violation prior to 30 days after
|
||||
your receipt of the notice.
|
||||
|
||||
Termination of your rights under this section does not terminate the
|
||||
licenses of parties who have received copies or rights from you under
|
||||
this License. If your rights have been terminated and not permanently
|
||||
reinstated, you do not qualify to receive new licenses for the same
|
||||
material under section 10.
|
||||
|
||||
9. Acceptance Not Required for Having Copies.
|
||||
|
||||
You are not required to accept this License in order to receive or
|
||||
run a copy of the Program. Ancillary propagation of a covered work
|
||||
occurring solely as a consequence of using peer-to-peer transmission
|
||||
to receive a copy likewise does not require acceptance. However,
|
||||
nothing other than this License grants you permission to propagate or
|
||||
modify any covered work. These actions infringe copyright if you do
|
||||
not accept this License. Therefore, by modifying or propagating a
|
||||
covered work, you indicate your acceptance of this License to do so.
|
||||
|
||||
10. Automatic Licensing of Downstream Recipients.
|
||||
|
||||
Each time you convey a covered work, the recipient automatically
|
||||
receives a license from the original licensors, to run, modify and
|
||||
propagate that work, subject to this License. You are not responsible
|
||||
for enforcing compliance by third parties with this License.
|
||||
|
||||
An "entity transaction" is a transaction transferring control of an
|
||||
organization, or substantially all assets of one, or subdividing an
|
||||
organization, or merging organizations. If propagation of a covered
|
||||
work results from an entity transaction, each party to that
|
||||
transaction who receives a copy of the work also receives whatever
|
||||
licenses to the work the party's predecessor in interest had or could
|
||||
give under the previous paragraph, plus a right to possession of the
|
||||
Corresponding Source of the work from the predecessor in interest, if
|
||||
the predecessor has it or can get it with reasonable efforts.
|
||||
|
||||
You may not impose any further restrictions on the exercise of the
|
||||
rights granted or affirmed under this License. For example, you may
|
||||
not impose a license fee, royalty, or other charge for exercise of
|
||||
rights granted under this License, and you may not initiate litigation
|
||||
(including a cross-claim or counterclaim in a lawsuit) alleging that
|
||||
any patent claim is infringed by making, using, selling, offering for
|
||||
sale, or importing the Program or any portion of it.
|
||||
|
||||
11. Patents.
|
||||
|
||||
A "contributor" is a copyright holder who authorizes use under this
|
||||
License of the Program or a work on which the Program is based. The
|
||||
work thus licensed is called the contributor's "contributor version".
|
||||
|
||||
A contributor's "essential patent claims" are all patent claims
|
||||
owned or controlled by the contributor, whether already acquired or
|
||||
hereafter acquired, that would be infringed by some manner, permitted
|
||||
by this License, of making, using, or selling its contributor version,
|
||||
but do not include claims that would be infringed only as a
|
||||
consequence of further modification of the contributor version. For
|
||||
purposes of this definition, "control" includes the right to grant
|
||||
patent sublicenses in a manner consistent with the requirements of
|
||||
this License.
|
||||
|
||||
Each contributor grants you a non-exclusive, worldwide, royalty-free
|
||||
patent license under the contributor's essential patent claims, to
|
||||
make, use, sell, offer for sale, import and otherwise run, modify and
|
||||
propagate the contents of its contributor version.
|
||||
|
||||
In the following three paragraphs, a "patent license" is any express
|
||||
agreement or commitment, however denominated, not to enforce a patent
|
||||
(such as an express permission to practice a patent or covenant not to
|
||||
sue for patent infringement). To "grant" such a patent license to a
|
||||
party means to make such an agreement or commitment not to enforce a
|
||||
patent against the party.
|
||||
|
||||
If you convey a covered work, knowingly relying on a patent license,
|
||||
and the Corresponding Source of the work is not available for anyone
|
||||
to copy, free of charge and under the terms of this License, through a
|
||||
publicly available network server or other readily accessible means,
|
||||
then you must either (1) cause the Corresponding Source to be so
|
||||
available, or (2) arrange to deprive yourself of the benefit of the
|
||||
patent license for this particular work, or (3) arrange, in a manner
|
||||
consistent with the requirements of this License, to extend the patent
|
||||
license to downstream recipients. "Knowingly relying" means you have
|
||||
actual knowledge that, but for the patent license, your conveying the
|
||||
covered work in a country, or your recipient's use of the covered work
|
||||
in a country, would infringe one or more identifiable patents in that
|
||||
country that you have reason to believe are valid.
|
||||
|
||||
If, pursuant to or in connection with a single transaction or
|
||||
arrangement, you convey, or propagate by procuring conveyance of, a
|
||||
covered work, and grant a patent license to some of the parties
|
||||
receiving the covered work authorizing them to use, propagate, modify
|
||||
or convey a specific copy of the covered work, then the patent license
|
||||
you grant is automatically extended to all recipients of the covered
|
||||
work and works based on it.
|
||||
|
||||
A patent license is "discriminatory" if it does not include within
|
||||
the scope of its coverage, prohibits the exercise of, or is
|
||||
conditioned on the non-exercise of one or more of the rights that are
|
||||
specifically granted under this License. You may not convey a covered
|
||||
work if you are a party to an arrangement with a third party that is
|
||||
in the business of distributing software, under which you make payment
|
||||
to the third party based on the extent of your activity of conveying
|
||||
the work, and under which the third party grants, to any of the
|
||||
parties who would receive the covered work from you, a discriminatory
|
||||
patent license (a) in connection with copies of the covered work
|
||||
conveyed by you (or copies made from those copies), or (b) primarily
|
||||
for and in connection with specific products or compilations that
|
||||
contain the covered work, unless you entered into that arrangement,
|
||||
or that patent license was granted, prior to 28 March 2007.
|
||||
|
||||
Nothing in this License shall be construed as excluding or limiting
|
||||
any implied license or other defenses to infringement that may
|
||||
otherwise be available to you under applicable patent law.
|
||||
|
||||
12. No Surrender of Others' Freedom.
|
||||
|
||||
If conditions are imposed on you (whether by court order, agreement or
|
||||
otherwise) that contradict the conditions of this License, they do not
|
||||
excuse you from the conditions of this License. If you cannot convey a
|
||||
covered work so as to satisfy simultaneously your obligations under this
|
||||
License and any other pertinent obligations, then as a consequence you may
|
||||
not convey it at all. For example, if you agree to terms that obligate you
|
||||
to collect a royalty for further conveying from those to whom you convey
|
||||
the Program, the only way you could satisfy both those terms and this
|
||||
License would be to refrain entirely from conveying the Program.
|
||||
|
||||
13. Use with the GNU Affero General Public License.
|
||||
|
||||
Notwithstanding any other provision of this License, you have
|
||||
permission to link or combine any covered work with a work licensed
|
||||
under version 3 of the GNU Affero General Public License into a single
|
||||
combined work, and to convey the resulting work. The terms of this
|
||||
License will continue to apply to the part which is the covered work,
|
||||
but the special requirements of the GNU Affero General Public License,
|
||||
section 13, concerning interaction through a network will apply to the
|
||||
combination as such.
|
||||
|
||||
14. Revised Versions of this License.
|
||||
|
||||
The Free Software Foundation may publish revised and/or new versions of
|
||||
the GNU General Public License from time to time. Such new versions will
|
||||
be similar in spirit to the present version, but may differ in detail to
|
||||
address new problems or concerns.
|
||||
|
||||
Each version is given a distinguishing version number. If the
|
||||
Program specifies that a certain numbered version of the GNU General
|
||||
Public License "or any later version" applies to it, you have the
|
||||
option of following the terms and conditions either of that numbered
|
||||
version or of any later version published by the Free Software
|
||||
Foundation. If the Program does not specify a version number of the
|
||||
GNU General Public License, you may choose any version ever published
|
||||
by the Free Software Foundation.
|
||||
|
||||
If the Program specifies that a proxy can decide which future
|
||||
versions of the GNU General Public License can be used, that proxy's
|
||||
public statement of acceptance of a version permanently authorizes you
|
||||
to choose that version for the Program.
|
||||
|
||||
Later license versions may give you additional or different
|
||||
permissions. However, no additional obligations are imposed on any
|
||||
author or copyright holder as a result of your choosing to follow a
|
||||
later version.
|
||||
|
||||
15. Disclaimer of Warranty.
|
||||
|
||||
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
|
||||
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
|
||||
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
|
||||
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
|
||||
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
|
||||
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
|
||||
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
|
||||
|
||||
16. Limitation of Liability.
|
||||
|
||||
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
|
||||
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
|
||||
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
|
||||
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
|
||||
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
|
||||
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
|
||||
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
|
||||
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
|
||||
SUCH DAMAGES.
|
||||
|
||||
17. Interpretation of Sections 15 and 16.
|
||||
|
||||
If the disclaimer of warranty and limitation of liability provided
|
||||
above cannot be given local legal effect according to their terms,
|
||||
reviewing courts shall apply local law that most closely approximates
|
||||
an absolute waiver of all civil liability in connection with the
|
||||
Program, unless a warranty or assumption of liability accompanies a
|
||||
copy of the Program in return for a fee.
|
||||
|
||||
END OF TERMS AND CONDITIONS
|
||||
|
||||
How to Apply These Terms to Your New Programs
|
||||
|
||||
If you develop a new program, and you want it to be of the greatest
|
||||
possible use to the public, the best way to achieve this is to make it
|
||||
free software which everyone can redistribute and change under these terms.
|
||||
|
||||
To do so, attach the following notices to the program. It is safest
|
||||
to attach them to the start of each source file to most effectively
|
||||
state the exclusion of warranty; and each file should have at least
|
||||
the "copyright" line and a pointer to where the full notice is found.
|
||||
|
||||
<one line to give the program's name and a brief idea of what it does.>
|
||||
Copyright (C) <year> <name of author>
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
|
||||
Also add information on how to contact you by electronic and paper mail.
|
||||
|
||||
If the program does terminal interaction, make it output a short
|
||||
notice like this when it starts in an interactive mode:
|
||||
|
||||
<program> Copyright (C) <year> <name of author>
|
||||
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
|
||||
This is free software, and you are welcome to redistribute it
|
||||
under certain conditions; type `show c' for details.
|
||||
|
||||
The hypothetical commands `show w' and `show c' should show the appropriate
|
||||
parts of the General Public License. Of course, your program's commands
|
||||
might be different; for a GUI interface, you would use an "about box".
|
||||
|
||||
You should also get your employer (if you work as a programmer) or school,
|
||||
if any, to sign a "copyright disclaimer" for the program, if necessary.
|
||||
For more information on this, and how to apply and follow the GNU GPL, see
|
||||
<https://www.gnu.org/licenses/>.
|
||||
|
||||
The GNU General Public License does not permit incorporating your program
|
||||
into proprietary programs. If your program is a subroutine library, you
|
||||
may consider it more useful to permit linking proprietary applications with
|
||||
the library. If this is what you want to do, use the GNU Lesser General
|
||||
Public License instead of this License. But first, please read
|
||||
<https://www.gnu.org/licenses/why-not-lgpl.html>.
|
139
components/DendoStepper/README.md
Normal file
@ -0,0 +1,139 @@
|
||||
# DendoStepper
|
||||
|
||||
Work in progress, maybe unstable. Opening issues is more than welcome.
|
||||
This library takes care of pulse generating for stepper motor drivers with STEP/DIR interface. Pulse generating utilizes general purpose timers to achieve some usable accuracy and smoothness.
|
||||
Currently supports only linear acceleration and deceleration.
|
||||
|
||||
### Known limitations
|
||||
- maximum number of controlled stepper motors is 4, this is limited by number of general purpose timers
|
||||
- If the motor is moving, it is not possible to move it to another direction.
|
||||
|
||||
## Usage
|
||||
|
||||
```c++
|
||||
typedef struct
|
||||
{
|
||||
uint8_t stepPin; /** step signal pin */
|
||||
uint8_t dirPin; /** dir signal pin */
|
||||
uint8_t enPin; /** enable 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 */
|
||||
microStepping_t miStep; /** microstepping configured on driver - used in distance calculation */
|
||||
float stepAngle; /** one step angle in degrees (usually 1.8deg), used in steps per rotation calculation */
|
||||
} DendoStepper_config_t;
|
||||
|
||||
enum microStepping_t
|
||||
{
|
||||
MICROSTEP_1 = 0x1,
|
||||
MICROSTEP_2,
|
||||
MICROSTEP_4 = 0x4,
|
||||
MICROSTEP_8 = 0x8,
|
||||
MICROSTEP_16 = 0x10,
|
||||
MICROSTEP_32 = 0x20,
|
||||
MICROSTEP_64 = 0x40,
|
||||
MICROSTEP_128 = 0x80,
|
||||
MICROSTEP_256 = 0x100,
|
||||
};
|
||||
|
||||
```
|
||||
Configuration struct, can be allocated on stack or heap.
|
||||
|
||||
```c++
|
||||
void init();
|
||||
```
|
||||
Initializes GPIO and Timer peripherals, registers ISR. Expects populated config struct is alreay passed to the class using config()
|
||||
|
||||
```c++
|
||||
void config(DendoStepper_config_t* config);
|
||||
```
|
||||
Configures the class as per passed config struct pointer.
|
||||
|
||||
```c++
|
||||
void setStepsPerMm(uint16_t steps);
|
||||
uint16_t getStepsPerMm();
|
||||
```
|
||||
Sets or gets steps needed to move one millimiter, useful if stepper is moving along linear axis.
|
||||
|
||||
```c++
|
||||
void setSpeed(uint16_t speed,uint16_t accT, uint16_t decT);
|
||||
uint16_t getSpeed();
|
||||
float getAcc();
|
||||
```
|
||||
Sets maximum speed in steps per second, acceleration and deceleration time in milliseconds.
|
||||
Gets speed in steps per second
|
||||
Gets acceleration in steps per second per second
|
||||
|
||||
```c++
|
||||
void setSpeedMm(uint16_t speed,uint16_t accT, uint16_t decT);
|
||||
```
|
||||
Sets maximum speed in mm/s, acceleration and deceleration time in milliseconds. Expects already defined steps per millimeter with setStepsPerMm()
|
||||
|
||||
```c++
|
||||
void runPos(int32_t relative);
|
||||
```
|
||||
Runs motor to position relative from current position in steps, respecting constraints set with setSpeed()
|
||||
|
||||
```c++
|
||||
void runPosMm(int32_t relative);
|
||||
```
|
||||
Runs motor to position relative from current position in millimeters, respecting constraints set with setSpeed()
|
||||
Expects already defined steps per millimeter with setStepsPerMm()
|
||||
|
||||
```c++
|
||||
bool runAbsolute(uint32_t position);
|
||||
```
|
||||
Runs motor in absolute coordinate plane. Unit: steps (should be constrained with home switch)
|
||||
|
||||
```c++
|
||||
bool runAbsoluteMm(uint32_t position);
|
||||
```
|
||||
Runs motor in absolute coordinate plane. Unit: millimeters (should be constrained with home switch)
|
||||
Expects already defined steps per millimeter with setStepsPerMm()
|
||||
|
||||
```c++
|
||||
bool runInf(bool direction);
|
||||
```
|
||||
Runs motor infintely in desired direction with constrains set using setSpeed().
|
||||
|
||||
```c++
|
||||
void disableMotor();
|
||||
void enableMotor();
|
||||
```
|
||||
Disables and enables motor via EN pin
|
||||
|
||||
```c++
|
||||
uint8_t getState();
|
||||
|
||||
enum motor_status{
|
||||
DISABLED,
|
||||
IDLE,
|
||||
ACC,
|
||||
COAST,
|
||||
DEC,
|
||||
};
|
||||
```
|
||||
Returns current state of motor, return type is enum motor_status
|
||||
|
||||
|
||||
```c++
|
||||
void resetAbsolute();
|
||||
```
|
||||
Resets absolute position to 0. Called for ex. when endswitch is hit.
|
||||
|
||||
```c++
|
||||
void getPosition();
|
||||
```
|
||||
Gets current position in absolute coordinate plane in steps.
|
||||
|
||||
```c++
|
||||
void getPositionMm();
|
||||
```
|
||||
Gets current position in absolute coordinate plane in millimeters.
|
||||
Expects already defined steps per millimeter with setStepsPerMm()
|
||||
|
||||
```c++
|
||||
void stop();
|
||||
```
|
||||
Stops the motor dead on the spot. No deceleration is performed this way. Eg. e-stop.
|
||||
|
||||
|
0
components/DendoStepper/component.mk
Normal file
3
components/DendoStepper/example/.gitignore
vendored
Normal file
@ -0,0 +1,3 @@
|
||||
build/
|
||||
sdkconfig
|
||||
sdkconfig.old
|
9
components/DendoStepper/example/CMakeLists.txt
Normal file
@ -0,0 +1,9 @@
|
||||
# For more information about build system see
|
||||
# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html
|
||||
# The following five lines of boilerplate have to be in your project's
|
||||
# CMakeLists in this exact order for cmake to work correctly
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
|
||||
set(EXTRA_COMPONENT_DIRS "../")
|
||||
project(example)
|
32
components/DendoStepper/example/README.md
Normal file
@ -0,0 +1,32 @@
|
||||
# _Sample project_
|
||||
|
||||
(See the README.md file in the upper level 'examples' directory for more information about examples.)
|
||||
|
||||
This is the simplest buildable example. The example is used by command `idf.py create-project`
|
||||
that copies the project to user specified path and set it's name. For more information follow the [docs page](https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html#start-a-new-project)
|
||||
|
||||
|
||||
|
||||
## How to use example
|
||||
We encourage the users to use the example as a template for the new projects.
|
||||
A recommended way is to follow the instructions on a [docs page](https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html#start-a-new-project).
|
||||
|
||||
## Example folder contents
|
||||
|
||||
The project **sample_project** contains one source file in C language [main.c](main/main.c). The file is located in folder [main](main).
|
||||
|
||||
ESP-IDF projects are built using CMake. The project build configuration is contained in `CMakeLists.txt`
|
||||
files that provide set of directives and instructions describing the project's source files and targets
|
||||
(executable, library, or both).
|
||||
|
||||
Below is short explanation of remaining files in the project folder.
|
||||
|
||||
```
|
||||
├── CMakeLists.txt
|
||||
├── main
|
||||
│ ├── CMakeLists.txt
|
||||
│ └── main.c
|
||||
└── README.md This is the file you are currently reading
|
||||
```
|
||||
Additionally, the sample project contains Makefile and component.mk files, used for the legacy Make based build system.
|
||||
They are not used or needed when building with CMake and idf.py.
|
3
components/DendoStepper/example/main/CMakeLists.txt
Normal file
@ -0,0 +1,3 @@
|
||||
idf_component_register(SRCS "main.cpp"
|
||||
INCLUDE_DIRS "."
|
||||
REQUIRES DendoStepper freertos)
|
49
components/DendoStepper/example/main/main.cpp
Normal file
@ -0,0 +1,49 @@
|
||||
#include <stdio.h>
|
||||
#include "DendoStepper.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_log.h"
|
||||
|
||||
DendoStepper step;
|
||||
DendoStepper step1;
|
||||
|
||||
extern "C" void app_main(void)
|
||||
{
|
||||
DendoStepper_config_t step_cfg = {
|
||||
.stepPin = 16,
|
||||
.dirPin = 17,
|
||||
.enPin = 15,
|
||||
.timer_group = TIMER_GROUP_0,
|
||||
.timer_idx = TIMER_0,
|
||||
.miStep = MICROSTEP_32,
|
||||
.stepAngle = 1.8};
|
||||
|
||||
DendoStepper_config_t step1_cfg = {
|
||||
.stepPin = 18,
|
||||
.dirPin = 19,
|
||||
.enPin = 20,
|
||||
.timer_group = TIMER_GROUP_0,
|
||||
.timer_idx = TIMER_1,
|
||||
.miStep = MICROSTEP_32,
|
||||
.stepAngle = 1.8};
|
||||
|
||||
step.config(&step_cfg);
|
||||
step1.config(&step1_cfg);
|
||||
|
||||
step.init();
|
||||
step1.init();
|
||||
|
||||
step.setSpeed(10000, 1000, 1000);
|
||||
step1.setSpeed(20000, 1000, 1000);
|
||||
|
||||
// step.runInf(true);
|
||||
step.setStepsPerMm(10);
|
||||
|
||||
while (1)
|
||||
{
|
||||
step.runPosMm(500);
|
||||
step1.runPos(10000);
|
||||
vTaskDelay(1000);
|
||||
// step.runAbs(5000);
|
||||
}
|
||||
}
|
281
components/DendoStepper/include/DendoStepper.h
Normal file
@ -0,0 +1,281 @@
|
||||
#pragma once
|
||||
|
||||
/* ESP-IDF library for bipolar stepper motor drivers with STEP/DIR interface
|
||||
Copyright (C) 2022 Denis Voltmann
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef DENDOSTEPPER_H
|
||||
#define DENDOSTEPPER_H
|
||||
|
||||
#include "stdint.h"
|
||||
#include "stdio.h"
|
||||
#include <cstring>
|
||||
#include "driver/timer.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_timer.h"
|
||||
#include "math.h"
|
||||
|
||||
//#define STEP_DEBUG
|
||||
|
||||
#define NS_TO_T_TICKS(x) (x)
|
||||
#define TIMER_F 1000000ULL
|
||||
#define TICK_PER_S TIMER_F
|
||||
|
||||
enum motor_status
|
||||
{
|
||||
DISABLED,
|
||||
IDLE,
|
||||
ACC,
|
||||
COAST,
|
||||
DEC
|
||||
};
|
||||
|
||||
enum dir
|
||||
{
|
||||
CW,
|
||||
CCW
|
||||
};
|
||||
|
||||
enum microStepping_t
|
||||
{
|
||||
MICROSTEP_1 = 0x1,
|
||||
MICROSTEP_2,
|
||||
MICROSTEP_4 = 0x4,
|
||||
MICROSTEP_8 = 0x8,
|
||||
MICROSTEP_16 = 0x10,
|
||||
MICROSTEP_32 = 0x20,
|
||||
MICROSTEP_64 = 0x40,
|
||||
MICROSTEP_128 = 0x80,
|
||||
MICROSTEP_256 = 0x100,
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Configuration structure
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t stepPin; /** step signal pin */
|
||||
uint8_t dirPin; /** dir signal pin */
|
||||
uint8_t enPin; /** enable 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 */
|
||||
microStepping_t miStep; /** microstepping configured on driver - used in distance calculation */
|
||||
float stepAngle; /** one step angle in degrees (usually 1.8deg), used in steps per rotation calculation */
|
||||
} DendoStepper_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;
|
||||
int32_t stepsRemaining = 0;
|
||||
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;
|
||||
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;
|
||||
|
||||
class DendoStepper
|
||||
{
|
||||
private:
|
||||
DendoStepper_config_t conf;
|
||||
ctrl_var_t ctrl;
|
||||
esp_timer_handle_t dyingTimer;
|
||||
TaskHandle_t enTask;
|
||||
uint64_t currentPos = 0; // absolute position
|
||||
bool timerStarted = 0;
|
||||
|
||||
/** @brief PRIVATE: Step interval calculation
|
||||
* @param speed maximum movement speed
|
||||
* @param accTimeMs acceleration time in ms
|
||||
* @param target target position
|
||||
*/
|
||||
void calc(uint32_t);
|
||||
|
||||
/** @brief sets En GPIO
|
||||
* @param state 0-LOW,1-HIGH
|
||||
* @return void
|
||||
*/
|
||||
void setEn(bool);
|
||||
|
||||
/** @brief sets Dir GPIO
|
||||
* @param state 0-CW 1-CCW
|
||||
*/
|
||||
void setDir(bool);
|
||||
|
||||
/** @brief static wrapper for ISR function
|
||||
* @param _this DendoStepper* this pointer
|
||||
* @return bool
|
||||
*/
|
||||
static bool xISRwrap(void *_this)
|
||||
{
|
||||
return static_cast<DendoStepper *>(_this)->xISR();
|
||||
}
|
||||
|
||||
/** @brief enableMotor wrapper
|
||||
*/
|
||||
static void _disableMotor(void *_this)
|
||||
{
|
||||
static_cast<DendoStepper *>(_this)->disableMotor();
|
||||
}
|
||||
|
||||
bool xISR();
|
||||
|
||||
public:
|
||||
/** @brief Costructor - conf variables to be passed later
|
||||
*/
|
||||
DendoStepper();
|
||||
|
||||
/** @brief Configuration of library, used with constructor w/o params
|
||||
* @param config DendoStepper_config_t structure pointer - can be freed after this call
|
||||
*/
|
||||
void config(DendoStepper_config_t *config);
|
||||
|
||||
/** @brief initialize GPIO and Timer peripherals
|
||||
* @param stepP step pulse pin
|
||||
* @param dirP direction signal pin
|
||||
* @param enP enable signal Pin
|
||||
* @param group timer group to use (0 or 1)
|
||||
* @param index which timer to use (0 or 1)
|
||||
* @param microstepping microstepping performed by the driver, used for more accuracy
|
||||
* @param stepsPerRot how many steps it takes for the motor to move 2Pi rads. this can be also used instead of microstepping parameter
|
||||
*/
|
||||
void init(uint8_t, uint8_t, uint8_t, timer_group_t, timer_idx_t, microStepping_t microstep, uint16_t stepsPerRot);
|
||||
|
||||
/** @brief initialize GPIO and Timer peripherals, class must be configured beforehand with @attention config()
|
||||
*/
|
||||
void init();
|
||||
|
||||
/** @brief runs motor to relative position in steps
|
||||
* @param relative number of steps to run, negative is reverse
|
||||
*/
|
||||
esp_err_t runPos(int32_t relative);
|
||||
|
||||
/** @brief runs motor to relative position in mm
|
||||
* @param relative number of mm to run, negative is reverse
|
||||
*/
|
||||
esp_err_t runPosMm(int32_t relative);
|
||||
|
||||
/** @brief run motor to position in absolute coordinates (steps)
|
||||
* @param postition absolute position in steps from home position (must be positive);
|
||||
* @return ESP_OK if motor can run immediately, ESP_ERR if it is currently moving
|
||||
*/
|
||||
esp_err_t runAbs(uint32_t position);
|
||||
|
||||
/** @brief run motor to position in absolute coordinates (millimiters)
|
||||
* @param postition absolute position in mm from home position (must be positive);
|
||||
* @return ESP_OK if motor can run immediately, ESP_ERR if it is currently moving
|
||||
*/
|
||||
esp_err_t runAbsMm(uint32_t position);
|
||||
|
||||
/** @brief sets motor speed
|
||||
* @param speed speed in steps per second
|
||||
* @param accT acceleration time in ms
|
||||
* @param decT deceleration time in ms
|
||||
*/
|
||||
void setSpeed(uint32_t speed, uint16_t accT, uint16_t decT);
|
||||
|
||||
/** @brief sets motor speed and accel in millimeters/second
|
||||
* @param speed speed mm*s^-1
|
||||
* @param accT acceleration time in ms
|
||||
* @param accT deceleration time in ms
|
||||
*/
|
||||
void setSpeedMm(uint32_t speed, uint16_t accT, uint16_t decT);
|
||||
|
||||
//CUSTOM: change speed while running
|
||||
void changeSpeedMm(uint32_t speed);
|
||||
|
||||
/**
|
||||
* @brief Set steps per 1 mm of linear movement
|
||||
*
|
||||
* @param steps steps needed to move one millimiter
|
||||
*/
|
||||
void setStepsPerMm(uint16_t steps);
|
||||
|
||||
/**
|
||||
* @brief get steps per 1mm settings
|
||||
*
|
||||
*/
|
||||
uint16_t getStepsPerMm();
|
||||
|
||||
/** @brief set EN pin 1, stops movement
|
||||
*/
|
||||
void disableMotor();
|
||||
|
||||
/** @brief set EN pin to 0, enables movement
|
||||
*/
|
||||
void enableMotor();
|
||||
|
||||
/** @brief returns current state
|
||||
* @return motor_status enum
|
||||
*/
|
||||
uint8_t getState();
|
||||
|
||||
/** @brief run motor to position in absolute coordinates (millimiters)
|
||||
* @param postition absolute position in steps from home position (must be positive);
|
||||
* @return ESP_OK if motor can run immediately, ESP_ERR if it is currently moving
|
||||
*/
|
||||
esp_err_t runAbsoluteMm(uint32_t position);
|
||||
|
||||
/** @brief returns current absolute position
|
||||
* @return current absolute postion in steps
|
||||
*/
|
||||
uint64_t getPosition();
|
||||
|
||||
/** @brief returns current absolute position
|
||||
* @return current absolute postion in steps
|
||||
*/
|
||||
uint64_t getPositionMm();
|
||||
|
||||
/** @brief resets absolute pos to 0
|
||||
*/
|
||||
void resetAbsolute();
|
||||
|
||||
/** @brief
|
||||
*
|
||||
*/
|
||||
void runInf(bool direction);
|
||||
|
||||
/** @brief returns current speed in steps per second
|
||||
*/
|
||||
uint16_t getSpeed();
|
||||
|
||||
/** @brief returns current acceleration time in ms
|
||||
*/
|
||||
float getAcc();
|
||||
|
||||
/** @brief stops the motor dead, but stays enabled
|
||||
*/
|
||||
void stop();
|
||||
};
|
||||
|
||||
#endif
|
BIN
docs/control-board_schematic.pdf
Normal file
Before Width: | Height: | Size: 31 KiB After Width: | Height: | Size: 31 KiB |
BIN
docs/linear-axis_dimensions.jpg
Normal file
After Width: | Height: | Size: 594 KiB |
Before Width: | Height: | Size: 60 KiB After Width: | Height: | Size: 60 KiB |
Before Width: | Height: | Size: 54 KiB After Width: | Height: | Size: 54 KiB |
BIN
docs/stepper-driver_MKS-SERVO28C-manual.pdf
Normal file
BIN
docs/stepper-driver_TB6600-Manual.pdf
Normal file
Before Width: | Height: | Size: 126 KiB After Width: | Height: | Size: 126 KiB |
BIN
docs/vfd/T13-400W-12-H_scan.PDF
Normal file
BIN
docs/vfd/modbus-test/setfreq.jpg
Normal file
After Width: | Height: | Size: 144 KiB |
BIN
docs/vfd/modbus-test/start.jpg
Normal file
After Width: | Height: | Size: 128 KiB |
BIN
docs/vfd/modbus-test/stop.jpg
Normal file
After Width: | Height: | Size: 144 KiB |
BIN
img/cable-length-cutter.jpg
Normal file
After Width: | Height: | Size: 546 KiB |
3
img/panel-layout.svg
Normal file
After Width: | Height: | Size: 348 KiB |
@ -1,13 +1,20 @@
|
||||
idf_component_register(
|
||||
SRCS
|
||||
"main.cpp"
|
||||
"config.cpp"
|
||||
"global.cpp"
|
||||
"control.cpp"
|
||||
"buzzer.cpp"
|
||||
"vfd.cpp"
|
||||
"display.cpp"
|
||||
"cutter.cpp"
|
||||
"switchesAnalog.cpp"
|
||||
"stepper.cpp"
|
||||
"guide-stepper.cpp"
|
||||
"encoder.cpp"
|
||||
"shutdown.cpp"
|
||||
INCLUDE_DIRS
|
||||
"."
|
||||
)
|
||||
|
||||
# colored build output (errors, warnings...)
|
||||
idf_build_set_property(COMPILE_OPTIONS "-fdiagnostics-color=always" APPEND)
|
@ -1,5 +1,5 @@
|
||||
#include "buzzer.hpp"
|
||||
#include "config.hpp"
|
||||
#include "config.h"
|
||||
|
||||
static const char *TAG_BUZZER = "buzzer";
|
||||
|
||||
|
@ -1,24 +1,21 @@
|
||||
#pragma once
|
||||
extern "C" {
|
||||
#include "driver/adc.h"
|
||||
}
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "switchesAnalog.hpp"
|
||||
|
||||
#include "esp_idf_version.h"
|
||||
|
||||
//note: global variables and objects were moved to global.hpp
|
||||
|
||||
//===================================
|
||||
//===== define output gpio pins =====
|
||||
//===================================
|
||||
//4x stepper mosfet outputs for VFD
|
||||
#define GPIO_VFD_FWD GPIO_NUM_4 //ST4
|
||||
#define GPIO_VFD_REV GPIO_NUM_16 //ST3
|
||||
#define GPIO_VFD_REV GPIO_NUM_5 //mos2
|
||||
#define GPIO_VFD_D0 GPIO_NUM_2 //ST2
|
||||
#define GPIO_VFD_D1 GPIO_NUM_15 //ST1
|
||||
//#define GPIO_VFD_D2 GPIO_NUM_15 //ST1 (D2 only used with 7.5kw vfd)
|
||||
|
||||
#define GPIO_MOS1 GPIO_NUM_18 //mos1 (free)
|
||||
#define GPIO_LAMP GPIO_NUM_5 //mos2
|
||||
#define GPIO_MOS1 GPIO_NUM_18 //mos1 (free) 2022.02.28: pin used for stepper
|
||||
#define GPIO_LAMP GPIO_NUM_0 //mos2 (5) 2022.02.28: lamp disabled, pin used for stepper
|
||||
#define GPIO_RELAY GPIO_NUM_13
|
||||
#define GPIO_BUZZER GPIO_NUM_12
|
||||
|
||||
@ -30,6 +27,12 @@ extern "C" {
|
||||
#define ADC_CHANNEL_POTI ADC1_CHANNEL_0
|
||||
#define GPIO_4SW_TO_ANALOG GPIO_NUM_39
|
||||
#define ADC_CHANNEL_4SW_TO_ANALOG ADC1_CHANNEL_3 //gpio 39
|
||||
|
||||
#define ADC_CHANNEL ADC_CHANNEL_0
|
||||
//#define ADC_LOW_VOLTAGE_THRESHOLD 1000 //adc value where shut down is detected (store certain values before power loss)
|
||||
#define GPIO_PIN GPIO_NUM_2
|
||||
|
||||
#define ADC_CHANNEL_SUPPLY_VOLTAGE ADC1_CHANNEL_7//gpio35 onboard supply voltage
|
||||
//ADC1_CHANNEL_0 gpio36
|
||||
//ADC1_CHANNEL_6 gpio_34
|
||||
//ADC1_CHANNEL_3 gpio_39
|
||||
@ -48,9 +51,8 @@ extern "C" {
|
||||
#define SW_PRESET3 sw_gpio_analog_3
|
||||
#define SW_CUT sw_gpio_33
|
||||
#define SW_AUTO_CUT sw_gpio_32
|
||||
|
||||
//unused but already available evaluated inputs
|
||||
//#define ? sw_gpio_34
|
||||
//note: actual objects are created in global.cpp
|
||||
|
||||
|
||||
|
||||
@ -70,6 +72,7 @@ extern "C" {
|
||||
#define DISPLAY_PIN_NUM_CLK GPIO_NUM_22
|
||||
#define DISPLAY_PIN_NUM_CS GPIO_NUM_27
|
||||
#define DISPLAY_DELAY 2000
|
||||
#define DISPLAY_BRIGHTNESS 8
|
||||
|
||||
//--------------------------
|
||||
//----- encoder config -----
|
||||
@ -79,46 +82,46 @@ extern "C" {
|
||||
#define ENABLE_HALF_STEPS false // Set to true to enable tracking of rotary encoder at half step resolution
|
||||
#define FLIP_DIRECTION false // Set to true to reverse the clockwise/counterclockwise sense
|
||||
|
||||
|
||||
|
||||
//--------------------------
|
||||
//----- stepper config -----
|
||||
//--------------------------
|
||||
//enable stepper test mode (dont start control and encoder task)
|
||||
//#define STEPPER_TEST
|
||||
//pins
|
||||
#define STEPPER_STEP_PIN GPIO_NUM_18 //mos1
|
||||
#define STEPPER_DIR_PIN GPIO_NUM_16 //ST3
|
||||
//driver settings
|
||||
#define STEPPER_STEPS_PER_MM (200/2) //steps/mm (steps-per-rot / spindle-slope)
|
||||
#define STEPPER_SPEED_DEFAULT 25 //mm/s
|
||||
#define STEPPER_SPEED_MIN 4 //mm/s - speed threshold at which stepper immediately starts/stops
|
||||
#define STEPPER_ACCEL_INC 3 //steps/s increment per cycle
|
||||
#define STEPPER_DECEL_INC 7 //steps/s decrement per cycle
|
||||
//options affecting movement are currently defined in guide-stepper.cpp
|
||||
|
||||
|
||||
|
||||
//--------------------------
|
||||
//------ calibration -------
|
||||
//--------------------------
|
||||
//enable mode encoder test for calibration
|
||||
//enable mode encoder test for calibration (determine ENCODER_STEPS_PER_METER)
|
||||
//if defined, displays always show length and steps instead of the normal messages
|
||||
//#define ENCODER_TEST
|
||||
//TODO: add way to calibrate without flashing -> enter calibration mode with certain button sequence, enter steps-per-meter with poti, store in nvs
|
||||
|
||||
//steps per meter
|
||||
#define STEPS_PER_METER 2127 //roll-v3-gummi-86.6mm - d=89.8mm
|
||||
//this value is determined experimentally while ENCODER_TEST is enabled
|
||||
//#define ENCODER_STEPS_PER_METER 2127 //until 2024.03.13 roll-v3-gummi-86.6mm - d=89.8mm
|
||||
#define ENCODER_STEPS_PER_METER 2118 //2024.03.13 roll-v3-gummi measured 86.5mm
|
||||
|
||||
//millimetres added to target length
|
||||
//millimeters added to target length
|
||||
//to ensure that length does not fall short when spool slightly rotates back after stop
|
||||
#define TARGET_LENGTH_OFFSET 0
|
||||
|
||||
//millimetres lengthNow can be below lengthTarget to still stay in target_reached state
|
||||
//millimeters lengthNow can be below lengthTarget to still stay in target_reached state
|
||||
#define TARGET_REACHED_TOLERANCE 5
|
||||
|
||||
|
||||
|
||||
|
||||
//============================
|
||||
//===== global variables =====
|
||||
//============================
|
||||
//create global evaluated switch objects
|
||||
//--- switches on digital gpio pins ---
|
||||
//extern gpio_evaluatedSwitch sw_gpio_39;
|
||||
extern gpio_evaluatedSwitch sw_gpio_34;
|
||||
extern gpio_evaluatedSwitch sw_gpio_32;
|
||||
extern gpio_evaluatedSwitch sw_gpio_33;
|
||||
extern gpio_evaluatedSwitch sw_gpio_25;
|
||||
extern gpio_evaluatedSwitch sw_gpio_26;
|
||||
extern gpio_evaluatedSwitch sw_gpio_14;
|
||||
|
||||
//--- switches connected to 4-sw-to-analog stripboard ---
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_0;
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_1;
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_2;
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_3;
|
||||
|
||||
|
||||
|
||||
//create global buzzer object
|
||||
extern buzzer_t buzzer;
|
233
main/control.cpp
@ -1,64 +1,68 @@
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include <esp_idf_version.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
|
||||
#include "max7219.h"
|
||||
|
||||
}
|
||||
#include <cmath>
|
||||
#include "config.h"
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "gpio_adc.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "vfd.hpp"
|
||||
#include "display.hpp"
|
||||
#include "cutter.hpp"
|
||||
#include "encoder.hpp"
|
||||
#include "guide-stepper.hpp"
|
||||
#include "global.hpp"
|
||||
#include "control.hpp"
|
||||
|
||||
|
||||
//========================
|
||||
//===== init encoder =====
|
||||
//========================
|
||||
QueueHandle_t init_encoder(rotary_encoder_info_t * info){
|
||||
// esp32-rotary-encoder requires that the GPIO ISR service is installed before calling rotary_encoder_register()
|
||||
ESP_ERROR_CHECK(gpio_install_isr_service(0));
|
||||
|
||||
// Initialise the rotary encoder device with the GPIOs for A and B signals
|
||||
ESP_ERROR_CHECK(rotary_encoder_init(info, ROT_ENC_A_GPIO, ROT_ENC_B_GPIO));
|
||||
ESP_ERROR_CHECK(rotary_encoder_enable_half_steps(info, ENABLE_HALF_STEPS));
|
||||
#ifdef FLIP_DIRECTION
|
||||
ESP_ERROR_CHECK(rotary_encoder_flip_direction(info));
|
||||
#endif
|
||||
|
||||
// Create a queue for events from the rotary encoder driver.
|
||||
// Tasks can read from this queue to receive up to date position information.
|
||||
QueueHandle_t event_queue = rotary_encoder_create_queue();
|
||||
ESP_ERROR_CHECK(rotary_encoder_set_queue(info, event_queue));
|
||||
return event_queue;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//====================
|
||||
//==== variables =====
|
||||
//====================
|
||||
//-----------------------------------------
|
||||
//--------------- variables ---------------
|
||||
//-----------------------------------------
|
||||
static const char *TAG = "control"; //tag for logging
|
||||
|
||||
//control
|
||||
const char* systemStateStr[7] = {"COUNTING", "WINDING_START", "WINDING", "TARGET_REACHED", "AUTO_CUT_WAITING", "CUTTING", "MANUAL"};
|
||||
systemState_t controlState = systemState_t::COUNTING;
|
||||
uint32_t timestamp_changedState = 0;
|
||||
static uint32_t timestamp_lastStateChange = 0;
|
||||
|
||||
char buf_disp[20]; //both displays
|
||||
char buf_disp1[10];// 8 digits + decimal point + \0
|
||||
char buf_disp2[10];// 8 digits + decimal point + \0
|
||||
char buf_tmp[15];
|
||||
//display
|
||||
static char buf_disp1[10];// 8 digits + decimal point + \0
|
||||
static char buf_disp2[10];// 8 digits + decimal point + \0
|
||||
static char buf_tmp[15];
|
||||
|
||||
rotary_encoder_info_t encoder; //encoder device/info
|
||||
QueueHandle_t encoder_queue = NULL; //encoder event queue
|
||||
rotary_encoder_state_t encoderState;
|
||||
|
||||
int lengthNow = 0; //length measured in mm
|
||||
int lengthTarget = 5000; //default target length in mm
|
||||
int lengthRemaining = 0; //(target - now) length needed for reaching the target
|
||||
int potiRead = 0; //voltage read from adc
|
||||
uint32_t timestamp_motorStarted = 0; //timestamp winding started
|
||||
//track length
|
||||
static int lengthNow = 0; //length measured in mm
|
||||
static int lengthTarget = 5000; //default target length in mm
|
||||
static int lengthRemaining = 0; //(target - now) length needed for reaching the target
|
||||
static int potiRead = 0; //voltage read from adc
|
||||
static uint32_t timestamp_motorStarted = 0; //timestamp winding started
|
||||
|
||||
//encoder test / calibration
|
||||
int lengthBeeped = 0; //only beep once per meter during encoder test
|
||||
|
||||
//automatic cut
|
||||
int cut_msRemaining = 0;
|
||||
uint32_t timestamp_cut_lastBeep = 0;
|
||||
uint32_t autoCut_delayMs = 2500; //TODO add this to config
|
||||
bool autoCutEnabled = false; //store state of toggle switch (no hotswitch)
|
||||
static int cut_msRemaining = 0;
|
||||
static uint32_t timestamp_cut_lastBeep = 0;
|
||||
static uint32_t autoCut_delayMs = 2500; //TODO add this to config
|
||||
static bool autoCutEnabled = false; //store state of toggle switch (no hotswitch)
|
||||
|
||||
|
||||
|
||||
//-----------------------------------------
|
||||
//--------------- functions ---------------
|
||||
//-----------------------------------------
|
||||
|
||||
//========================
|
||||
//===== change State =====
|
||||
//========================
|
||||
//function for changing the controlState with log output
|
||||
void changeState (systemState_t stateNew) {
|
||||
//only proceed when state actually changed
|
||||
@ -70,18 +74,21 @@ void changeState (systemState_t stateNew) {
|
||||
//change state
|
||||
controlState = stateNew;
|
||||
//update timestamp
|
||||
timestamp_changedState = esp_log_timestamp();
|
||||
timestamp_lastStateChange = esp_log_timestamp();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
//=================================
|
||||
//===== handle Stop Condition =====
|
||||
//function that checks whether start button is released or target is reached (used in multiple states)
|
||||
//returns true when stopped, false when no action
|
||||
//=================================
|
||||
//function that checks whether start button is released or target is reached
|
||||
//and takes according action if so (used in multiple states)
|
||||
//returns true when stop condition was met, false when no action required
|
||||
bool handleStopCondition(handledDisplay * displayTop, handledDisplay * displayBot){
|
||||
//--- stop conditions ---
|
||||
//stop conditions that are checked in any mode
|
||||
//target reached
|
||||
//target reached -> reached state, stop motor, display message
|
||||
if (lengthRemaining <= 0 ) {
|
||||
changeState(systemState_t::TARGET_REACHED);
|
||||
vfd_setState(false);
|
||||
@ -90,7 +97,7 @@ bool handleStopCondition(handledDisplay * displayTop, handledDisplay * displayBo
|
||||
buzzer.beep(2, 100, 100);
|
||||
return true;
|
||||
}
|
||||
//start button released
|
||||
//start button released -> idle state, stop motor, display message
|
||||
else if (SW_START.state == false) {
|
||||
changeState(systemState_t::COUNTING);
|
||||
vfd_setState(false);
|
||||
@ -104,8 +111,11 @@ bool handleStopCondition(handledDisplay * displayTop, handledDisplay * displayBo
|
||||
}
|
||||
|
||||
|
||||
|
||||
//===================================
|
||||
//===== set dynamic speed level =====
|
||||
//function that sets the vfd speed level dynamicly depending on the remaining distance
|
||||
//===================================
|
||||
//function that sets the vfd speed level dynamically depending on the remaining distance
|
||||
//closer to target -> slower
|
||||
void setDynSpeedLvl(uint8_t lvlMax = 3){
|
||||
uint8_t lvl;
|
||||
@ -133,33 +143,30 @@ void setDynSpeedLvl(uint8_t lvlMax = 3){
|
||||
//========================
|
||||
//===== control task =====
|
||||
//========================
|
||||
//task that controls the entire machine
|
||||
void task_control(void *pvParameter)
|
||||
{
|
||||
//initialize encoder
|
||||
encoder_queue = init_encoder(&encoder);
|
||||
|
||||
//initialize display
|
||||
//-- initialize display --
|
||||
max7219_t two7SegDisplays = display_init();
|
||||
//create two separate handled display instances
|
||||
//create two separate custom handled display instances
|
||||
handledDisplay displayTop(two7SegDisplays, 0);
|
||||
handledDisplay displayBot(two7SegDisplays, 8);
|
||||
|
||||
//--- display welcome msg ---
|
||||
//-- display welcome msg --
|
||||
//display welcome message on two 7 segment displays
|
||||
//currently show name and date and scrolling 'hello'
|
||||
display_ShowWelcomeMsg(two7SegDisplays);
|
||||
|
||||
|
||||
//================
|
||||
//===== loop =====
|
||||
//================
|
||||
// ##############################
|
||||
// ######## control loop ########
|
||||
// ##############################
|
||||
// repeatedly handle the machine
|
||||
while(1){
|
||||
vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
|
||||
//-----------------------------
|
||||
|
||||
//------ handle switches ------
|
||||
//-----------------------------
|
||||
//run handle functions for all switches
|
||||
//run handle functions for all switches used here
|
||||
SW_START.handle();
|
||||
SW_RESET.handle();
|
||||
SW_SET.handle();
|
||||
@ -170,29 +177,23 @@ void task_control(void *pvParameter)
|
||||
SW_AUTO_CUT.handle();
|
||||
|
||||
|
||||
//---------------------------
|
||||
//------ handle cutter ------
|
||||
//---------------------------
|
||||
//TODO: separate task for cutter?
|
||||
cutter_handle();
|
||||
|
||||
|
||||
//----------------------------
|
||||
//------ rotary encoder ------
|
||||
//----------------------------
|
||||
// Poll current position and direction
|
||||
rotary_encoder_get_state(&encoder, &encoderState);
|
||||
//--- calculate distance ---
|
||||
lengthNow = (float)encoderState.position * 1000 / STEPS_PER_METER;
|
||||
//get current length since last reset
|
||||
lengthNow = encoder_getLenMm();
|
||||
|
||||
|
||||
//---------------------------
|
||||
|
||||
//--------- buttons ---------
|
||||
//---------------------------
|
||||
//--- RESET switch ---
|
||||
//#### RESET switch ####
|
||||
if (SW_RESET.risingEdge) {
|
||||
//dont reset when press used for stopping pending auto-cut
|
||||
if (controlState != systemState_t::AUTO_CUT_WAITING) {
|
||||
rotary_encoder_reset(&encoder);
|
||||
guide_moveToZero(); //move axis guiding the cable to start position
|
||||
encoder_reset(); //reset length measurement
|
||||
lengthNow = 0;
|
||||
buzzer.beep(1, 700, 100);
|
||||
displayTop.blink(2, 100, 100, "1ST ");
|
||||
@ -201,7 +202,7 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
}
|
||||
|
||||
//--- CUT switch ---
|
||||
//### CUT switch ####
|
||||
//start cut cycle immediately
|
||||
if (SW_CUT.risingEdge) {
|
||||
//stop cutter if already running
|
||||
@ -224,7 +225,7 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
}
|
||||
|
||||
//--- AUTO_CUT toggle sw ---
|
||||
//#### AUTO_CUT toggle sw ####
|
||||
//beep at change
|
||||
if (SW_AUTO_CUT.risingEdge) {
|
||||
buzzer.beep(2, 100, 50);
|
||||
@ -243,7 +244,7 @@ void task_control(void *pvParameter)
|
||||
autoCutEnabled = false;
|
||||
}
|
||||
|
||||
//--- manual mode ---
|
||||
//#### manual mode ####
|
||||
//switch to manual motor control (2 buttons + poti)
|
||||
if ( SW_PRESET2.state && (SW_PRESET1.state || SW_PRESET3.state) && controlState != systemState_t::MANUAL ) {
|
||||
//enable manual control
|
||||
@ -251,7 +252,7 @@ void task_control(void *pvParameter)
|
||||
buzzer.beep(3, 100, 60);
|
||||
}
|
||||
|
||||
//--- set custom target length ---
|
||||
//##### SET switch #####
|
||||
//set target length to poti position when SET switch is pressed
|
||||
if (SW_SET.state == true) {
|
||||
//read adc
|
||||
@ -287,7 +288,7 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
|
||||
|
||||
//--- target length presets ---
|
||||
//##### target length preset buttons #####
|
||||
if (controlState != systemState_t::MANUAL) { //dont apply preset length while controlling motor with preset buttons
|
||||
if (SW_PRESET1.risingEdge) {
|
||||
lengthTarget = 5000;
|
||||
@ -307,16 +308,17 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
|
||||
|
||||
|
||||
//---------------------------
|
||||
//--------- control ---------
|
||||
//---------------------------
|
||||
//calculate length difference
|
||||
//statemachine handling the sequential winding process
|
||||
|
||||
//calculate current length difference
|
||||
lengthRemaining = lengthTarget - lengthNow + TARGET_LENGTH_OFFSET;
|
||||
|
||||
//--- statemachine ---
|
||||
switch (controlState) {
|
||||
case systemState_t::COUNTING: //no motor action
|
||||
case systemState_t::COUNTING: //no motor action, just show current length on display
|
||||
vfd_setState(false);
|
||||
//TODO check stop condition before starting - prevents motor from starting 2 cycles when already at target
|
||||
//--- start winding to length ---
|
||||
@ -332,6 +334,7 @@ void task_control(void *pvParameter)
|
||||
case systemState_t::WINDING_START: //wind slow for certain time
|
||||
//set vfd speed depending on remaining distance
|
||||
setDynSpeedLvl(1); //limit to speed lvl 1 (force slow start)
|
||||
//switch to WINDING state (full speed) when 3s have passed
|
||||
if (esp_log_timestamp() - timestamp_motorStarted > 3000) {
|
||||
changeState(systemState_t::WINDING);
|
||||
}
|
||||
@ -341,23 +344,23 @@ void task_control(void *pvParameter)
|
||||
|
||||
case systemState_t::WINDING: //wind fast, slow down when close
|
||||
//set vfd speed depending on remaining distance
|
||||
setDynSpeedLvl(); //slow down when close to target
|
||||
setDynSpeedLvl(); //set motor speed, slow down when close to target
|
||||
handleStopCondition(&displayTop, &displayBot); //stops if button released or target reached
|
||||
//TODO: cancel when there is no cable movement anymore e.g. empty / timeout?
|
||||
break;
|
||||
|
||||
case systemState_t::TARGET_REACHED:
|
||||
case systemState_t::TARGET_REACHED: //prevent further motor rotation and start auto-cut
|
||||
vfd_setState(false);
|
||||
//switch to counting state when no longer at or above target length
|
||||
if ( lengthNow < lengthTarget - TARGET_REACHED_TOLERANCE ) {
|
||||
changeState(systemState_t::COUNTING);
|
||||
}
|
||||
//switch initiate countdown to auto-cut
|
||||
//initiate countdown to auto-cut if enabled
|
||||
else if ( (autoCutEnabled)
|
||||
&& (esp_log_timestamp() - timestamp_changedState > 300) ) { //wait for dislay msg "reached" to finish
|
||||
&& (esp_log_timestamp() - timestamp_lastStateChange > 300) ) { //wait for dislay msg "reached" to finish
|
||||
changeState(systemState_t::AUTO_CUT_WAITING);
|
||||
}
|
||||
//show msg when trying to start, but target is reached
|
||||
//show msg when trying to start, but target is already reached (-> reset button has to be pressed)
|
||||
if (SW_START.risingEdge) {
|
||||
buzzer.beep(2, 50, 30);
|
||||
displayTop.blink(2, 600, 500, " S0LL ");
|
||||
@ -365,9 +368,8 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
break;
|
||||
|
||||
case systemState_t::AUTO_CUT_WAITING:
|
||||
//handle delayed start of cut
|
||||
cut_msRemaining = autoCut_delayMs - (esp_log_timestamp() - timestamp_changedState);
|
||||
case systemState_t::AUTO_CUT_WAITING: //handle delayed start of cut
|
||||
cut_msRemaining = autoCut_delayMs - (esp_log_timestamp() - timestamp_lastStateChange);
|
||||
//- countdown stop conditions -
|
||||
//stop with any button
|
||||
if (!autoCutEnabled
|
||||
@ -391,13 +393,14 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
break;
|
||||
|
||||
case systemState_t::CUTTING:
|
||||
case systemState_t::CUTTING: //prevent any action while cutter is active
|
||||
//exit when finished cutting
|
||||
if (cutter_isRunning() == false) {
|
||||
//TODO stop if start buttons released?
|
||||
changeState(systemState_t::COUNTING);
|
||||
//TODO reset automatically or wait for manual reset?
|
||||
rotary_encoder_reset(&encoder);
|
||||
guide_moveToZero(); //move axis guiding the cable to start position
|
||||
encoder_reset(); //reset length measurement
|
||||
lengthNow = 0;
|
||||
buzzer.beep(1, 700, 100);
|
||||
}
|
||||
@ -434,30 +437,34 @@ void task_control(void *pvParameter)
|
||||
}
|
||||
|
||||
|
||||
|
||||
#ifdef ENCODER_TEST
|
||||
//--------------------------
|
||||
//------ encoder test ------
|
||||
//--------------------------
|
||||
#ifdef ENCODER_TEST
|
||||
//mode for calibrating the cable length measurement (determine ENCODER_STEPS_PER_METER in config.h)
|
||||
//run display handle functions
|
||||
displayTop.handle();
|
||||
displayBot.handle();
|
||||
//-- show encoder steps on display1 ---
|
||||
sprintf(buf_disp1, "EN %05d", encoderState.position); //count
|
||||
sprintf(buf_disp1, "EN %05d", encoder_getSteps()); //count
|
||||
displayTop.showString(buf_disp1);
|
||||
//--- show converted distance on display2 ---
|
||||
sprintf(buf_disp2, "Met %5.3f", (float)lengthNow/1000); //m
|
||||
displayBot.showString(buf_disp2);
|
||||
//--- beep every 1m ---
|
||||
//note: only works precicely in forward/positive direction
|
||||
if (lengthNow % 1000 < 50) { //with tolerance in case of missed exact value
|
||||
if (fabs(lengthNow - lengthBeeped) >= 900) { //dont beep multiple times at same meter
|
||||
//TODO: add case for reverse direction. currently beeps 0.1 too early
|
||||
buzzer.beep(1, 400, 100 );
|
||||
//--- beep every 0.5m ---
|
||||
//note: only works precisely in forward/positive direction, in reverse it it beeps by tolerance too early
|
||||
static int lengthBeeped = 0;
|
||||
if (lengthNow % 500 < 50) { //with tolerance in case of missed exact value
|
||||
if (fabs(lengthNow - lengthBeeped) >= 400) { //dont beep multiple times at same distance
|
||||
//TODO: add case for reverse direction. currently beeps 50mm too early
|
||||
if (lengthNow % 1000 < 50) // 1m beep
|
||||
buzzer.beep(1, 400, 100);
|
||||
else // 0.5m beep
|
||||
buzzer.beep(1, 200, 100);
|
||||
lengthBeeped = lengthNow;
|
||||
}
|
||||
}
|
||||
#else
|
||||
#else //not in encoder calibration mode
|
||||
|
||||
//--------------------------
|
||||
//-------- display1 --------
|
||||
@ -477,7 +484,6 @@ void task_control(void *pvParameter)
|
||||
displayTop.showString(buf_disp1);
|
||||
}
|
||||
|
||||
|
||||
//--------------------------
|
||||
//-------- display2 --------
|
||||
//--------------------------
|
||||
@ -510,6 +516,7 @@ void task_control(void *pvParameter)
|
||||
displayBot.showString(buf_tmp);
|
||||
}
|
||||
|
||||
#endif // end else ifdef ENCODER_TEST
|
||||
|
||||
//----------------------------
|
||||
//------- control lamp -------
|
||||
@ -526,10 +533,6 @@ void task_control(void *pvParameter)
|
||||
gpio_set_level(GPIO_LAMP, 0);
|
||||
}
|
||||
|
||||
} //end while(1)
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
} //end task_control
|
||||
|
@ -1,35 +1,12 @@
|
||||
#pragma once
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include <esp_idf_version.h>
|
||||
#include "freertos/queue.h"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
|
||||
#include "rotary_encoder.h"
|
||||
#include "max7219.h"
|
||||
|
||||
}
|
||||
#include <cmath>
|
||||
|
||||
#include "config.hpp"
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "gpio_adc.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "vfd.hpp"
|
||||
#include "display.hpp"
|
||||
#include "cutter.hpp"
|
||||
|
||||
|
||||
|
||||
//enum describing the state of the system
|
||||
enum class systemState_t {COUNTING, WINDING_START, WINDING, TARGET_REACHED, AUTO_CUT_WAITING, CUTTING, MANUAL};
|
||||
|
||||
//array with enum as strings for logging states
|
||||
extern const char* systemStateStr[7];
|
||||
|
||||
|
||||
//task that controls the entire machine (has to be created as task in main function)
|
||||
void task_control(void *pvParameter);
|
||||
|
@ -1,4 +1,6 @@
|
||||
#include "cutter.hpp"
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
|
||||
const char* cutter_stateStr[5] = {"IDLE", "START", "CUTTING", "CANCELED", "TIMEOUT"}; //define strings for logging the state
|
||||
|
||||
@ -15,9 +17,9 @@ bool checkTimeout();
|
||||
//---------------------------
|
||||
//----- local variables -----
|
||||
//---------------------------
|
||||
cutter_state_t cutter_state = cutter_state_t::IDLE;
|
||||
uint32_t timestamp_turnedOn;
|
||||
uint32_t msTimeout = 3000;
|
||||
static cutter_state_t cutter_state = cutter_state_t::IDLE;
|
||||
static uint32_t timestamp_turnedOn;
|
||||
static uint32_t msTimeout = 3000;
|
||||
static const char *TAG = "cutter"; //tag for logging
|
||||
|
||||
|
||||
@ -39,7 +41,6 @@ void cutter_stop(){
|
||||
if(cutter_state != cutter_state_t::IDLE){
|
||||
setState(cutter_state_t::CANCELED);
|
||||
}
|
||||
//starts motor on state change
|
||||
}
|
||||
|
||||
|
||||
@ -131,7 +132,6 @@ void cutter_handle(){
|
||||
//SW_CUTTER_POS.minOnMs = 10;
|
||||
//SW_CUTTER_POS.minOffMs = 10;
|
||||
|
||||
|
||||
switch(cutter_state){
|
||||
case cutter_state_t::IDLE:
|
||||
case cutter_state_t::TIMEOUT:
|
||||
@ -142,14 +142,13 @@ void cutter_handle(){
|
||||
case cutter_state_t::START:
|
||||
//--- moved away from idle position ---
|
||||
//if (gpio_get_level(GPIO_CUTTER_POS_SW) == 0){ //contact closed
|
||||
if (SW_CUTTER_POS.state == true) { //contact closed -> not at idle pos
|
||||
if (SW_CUTTER_POS.state == true) { //contact closed -> not at idle pos anymore
|
||||
setState(cutter_state_t::CUTTING);
|
||||
}
|
||||
//--- timeout ---
|
||||
else {
|
||||
checkTimeout();
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case cutter_state_t::CUTTING:
|
||||
|
@ -1,5 +1,6 @@
|
||||
#include "display.hpp"
|
||||
|
||||
#include "config.h"
|
||||
|
||||
//=== variables ===
|
||||
static const char *TAG = "display"; //tag for logging
|
||||
@ -34,7 +35,7 @@ max7219_t display_init(){
|
||||
ESP_ERROR_CHECK(max7219_init_desc(&dev, HOST, MAX7219_MAX_CLOCK_SPEED_HZ, DISPLAY_PIN_NUM_CS));
|
||||
ESP_ERROR_CHECK(max7219_init(&dev));
|
||||
//0...15
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, 8)); //TODO add this to config
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, DISPLAY_BRIGHTNESS));
|
||||
return dev;
|
||||
//display = dev;
|
||||
ESP_LOGI(TAG, "initializing display - done");
|
||||
@ -50,7 +51,7 @@ void display_ShowWelcomeMsg(max7219_t dev){
|
||||
//show name and date
|
||||
ESP_LOGI(TAG, "showing startup message...");
|
||||
max7219_clear(&dev);
|
||||
max7219_draw_text_7seg(&dev, 0, "CUTTER 29.09.2022");
|
||||
max7219_draw_text_7seg(&dev, 0, "CUTTER 15.03.2024");
|
||||
// 1234567812 34 5678
|
||||
vTaskDelay(pdMS_TO_TICKS(700));
|
||||
//scroll "hello" over 2 displays
|
||||
@ -64,7 +65,7 @@ void display_ShowWelcomeMsg(max7219_t dev){
|
||||
//noticed rare bug that one display does not initialize / is not configured correctly after start
|
||||
//initialize display again after the welcome message in case it did not work the first time
|
||||
ESP_ERROR_CHECK(max7219_init(&dev));
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, 8)); //TODO add this to config
|
||||
ESP_ERROR_CHECK(max7219_set_brightness(&dev, DISPLAY_BRIGHTNESS));
|
||||
}
|
||||
|
||||
|
||||
@ -83,9 +84,9 @@ handledDisplay::handledDisplay(max7219_t displayDevice, uint8_t posStart_f) {
|
||||
|
||||
|
||||
|
||||
//--------------------------------
|
||||
//---------- showString ----------
|
||||
//--------------------------------
|
||||
//================================
|
||||
//========== showString ==========
|
||||
//================================
|
||||
//function that displays a given string on the display
|
||||
void handledDisplay::showString(const char * buf, uint8_t pos_f){
|
||||
//calculate actual absolute position
|
||||
@ -103,11 +104,11 @@ void handledDisplay::showString(const char * buf, uint8_t pos_f){
|
||||
|
||||
|
||||
//TODO: blinkStrings() and blink() are very similar - can be optimized?
|
||||
//only difficulty currently is the reset behaivor of blinkStrings through showString (blink does not reset)
|
||||
//only difficulty is the reset behaivor of blinkStrings through showString (blink does not reset)
|
||||
|
||||
//----------------------------------
|
||||
//---------- blinkStrings ----------
|
||||
//----------------------------------
|
||||
//==================================
|
||||
//========== blinkStrings ==========
|
||||
//==================================
|
||||
//function switches between two strings in a given interval
|
||||
void handledDisplay::blinkStrings(const char * strOn_f, const char * strOff_f, uint32_t msOn_f, uint32_t msOff_f){
|
||||
//copy/update variables
|
||||
@ -130,9 +131,9 @@ void handledDisplay::blinkStrings(const char * strOn_f, const char * strOff_f, u
|
||||
|
||||
|
||||
|
||||
//-------------------------------
|
||||
//------------ blink ------------
|
||||
//-------------------------------
|
||||
//===============================
|
||||
//============ blink ============
|
||||
//===============================
|
||||
//function triggers certain count and interval of off durations
|
||||
void handledDisplay::blink(uint8_t count_f, uint32_t msOn_f, uint32_t msOff_f, const char * strOff_f) {
|
||||
//copy/update parameters
|
||||
@ -156,9 +157,9 @@ void handledDisplay::blink(uint8_t count_f, uint32_t msOn_f, uint32_t msOff_f, c
|
||||
|
||||
|
||||
|
||||
//--------------------------------
|
||||
//------------ handle ------------
|
||||
//--------------------------------
|
||||
//================================
|
||||
//============ handle ============
|
||||
//================================
|
||||
//function that handles time based modes
|
||||
//writes text to the 7 segment display depending on the current mode
|
||||
void handledDisplay::handle() {
|
||||
|
@ -16,9 +16,8 @@ extern "C"
|
||||
#include <cstring>
|
||||
|
||||
|
||||
#include "config.hpp"
|
||||
|
||||
//function for initializing the display using configuration from macros in config.hpp
|
||||
//function for initializing the display using configuration from macros in config.h
|
||||
max7219_t display_init();
|
||||
|
||||
//show welcome message on the entire display
|
||||
@ -44,8 +43,8 @@ class handledDisplay {
|
||||
//TODO: blinkStrings and blink are very similar - optimize?
|
||||
//TODO: add 'scroll string' method
|
||||
|
||||
private:
|
||||
|
||||
private:
|
||||
//--- variables ---
|
||||
//config
|
||||
max7219_t dev;
|
||||
|
79
main/encoder.cpp
Normal file
@ -0,0 +1,79 @@
|
||||
extern "C" {
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
|
||||
#include "rotary_encoder.h"
|
||||
}
|
||||
|
||||
#include "encoder.hpp"
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
|
||||
|
||||
//----------------------------
|
||||
//----- global variables -----
|
||||
//----------------------------
|
||||
static rotary_encoder_info_t encoder; //encoder device/info
|
||||
QueueHandle_t encoder_queue = NULL; //encoder event queue
|
||||
|
||||
|
||||
|
||||
//-------------------------
|
||||
//------- functions -------
|
||||
//-------------------------
|
||||
|
||||
//======================
|
||||
//==== encoder_init ====
|
||||
//======================
|
||||
//initialize encoder and return event queue
|
||||
QueueHandle_t encoder_init(){
|
||||
// esp32-rotary-encoder requires that the GPIO ISR service is installed before calling rotary_encoder_register()
|
||||
ESP_ERROR_CHECK(gpio_install_isr_service(0));
|
||||
|
||||
// Initialise the rotary encoder device with the GPIOs for A and B signals
|
||||
ESP_ERROR_CHECK(rotary_encoder_init(&encoder, ROT_ENC_A_GPIO, ROT_ENC_B_GPIO));
|
||||
ESP_ERROR_CHECK(rotary_encoder_enable_half_steps(&encoder, ENABLE_HALF_STEPS));
|
||||
#ifdef FLIP_DIRECTION
|
||||
ESP_ERROR_CHECK(rotary_encoder_flip_direction(&encoder));
|
||||
#endif
|
||||
|
||||
// Create a queue for events from the rotary encoder driver.
|
||||
// Tasks can read from this queue to receive up to date position information.
|
||||
QueueHandle_t event_queue = rotary_encoder_create_queue();
|
||||
ESP_ERROR_CHECK(rotary_encoder_set_queue(&encoder, event_queue));
|
||||
return event_queue;
|
||||
}
|
||||
|
||||
|
||||
//========================
|
||||
//=== encoder_getSteps ===
|
||||
//========================
|
||||
//get steps counted since last reset
|
||||
int encoder_getSteps(){
|
||||
// Poll current position and direction
|
||||
rotary_encoder_state_t encoderState;
|
||||
rotary_encoder_get_state(&encoder, &encoderState);
|
||||
//calculate total distance since last reset
|
||||
return encoderState.position;
|
||||
}
|
||||
|
||||
|
||||
//========================
|
||||
//=== encoder_getLenMm ===
|
||||
//========================
|
||||
//get current length in Mm since last reset
|
||||
int encoder_getLenMm(){
|
||||
return (float)encoder_getSteps() * 1000 / ENCODER_STEPS_PER_METER;
|
||||
}
|
||||
|
||||
|
||||
//=======================
|
||||
//==== encoder_reset ====
|
||||
//=======================
|
||||
//reset counted steps / length to 0
|
||||
void encoder_reset(){
|
||||
rotary_encoder_reset(&encoder);
|
||||
return;
|
||||
}
|
38
main/encoder.hpp
Normal file
@ -0,0 +1,38 @@
|
||||
/* in this file all used functions from original rotary_encoder.h library are wrapped with custom functions to reduce global variables and duplicate code
|
||||
*/
|
||||
//TODO create a cpp class for an encoder?
|
||||
#pragma once
|
||||
extern "C" {
|
||||
#include <freertos/task.h>
|
||||
}
|
||||
|
||||
|
||||
|
||||
//----------------------------
|
||||
//----- global variables -----
|
||||
//----------------------------
|
||||
//TODO ignore global encoder queue, since it is not used?
|
||||
extern QueueHandle_t encoder_queue; //encoder event queue
|
||||
|
||||
|
||||
//-------------------------
|
||||
//------- functions -------
|
||||
//-------------------------
|
||||
|
||||
//--- encoder_init ---
|
||||
//init encoder
|
||||
QueueHandle_t encoder_init();
|
||||
|
||||
//--- encoder_getSteps ---
|
||||
//get steps counted since last reset
|
||||
int encoder_getSteps();
|
||||
|
||||
|
||||
//--- encoder_getLenMm ---
|
||||
//get current length in Mm since last reset
|
||||
int encoder_getLenMm();
|
||||
|
||||
|
||||
//--- encoder_reset ---
|
||||
//reset counted steps / length to 0
|
||||
void encoder_reset();
|
@ -1,4 +1,5 @@
|
||||
#include "config.hpp"
|
||||
#include "global.hpp"
|
||||
#include "config.h"
|
||||
|
||||
|
||||
//--- inputs ---
|
||||
@ -19,4 +20,4 @@ gpio_evaluatedSwitch sw_gpio_analog_2(&switchesAnalog_getState_sw2);
|
||||
gpio_evaluatedSwitch sw_gpio_analog_3(&switchesAnalog_getState_sw3);
|
||||
|
||||
//create buzzer object with no gap between beep events
|
||||
buzzer_t buzzer(GPIO_BUZZER, 0);
|
||||
buzzer_t buzzer(GPIO_BUZZER, 0);
|
33
main/global.hpp
Normal file
@ -0,0 +1,33 @@
|
||||
#pragma once
|
||||
|
||||
extern "C" {
|
||||
#include "driver/adc.h"
|
||||
}
|
||||
#include "gpio_evaluateSwitch.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "switchesAnalog.hpp"
|
||||
|
||||
//note: in the actual code macro variables to these objects from config.h are used as the objects names
|
||||
|
||||
//============================
|
||||
//===== global variables =====
|
||||
//============================
|
||||
//create global evaluated switch objects for all available pins
|
||||
//--- switches on digital gpio pins ---
|
||||
//extern gpio_evaluatedSwitch sw_gpio_39;
|
||||
extern gpio_evaluatedSwitch sw_gpio_34;
|
||||
extern gpio_evaluatedSwitch sw_gpio_32;
|
||||
extern gpio_evaluatedSwitch sw_gpio_33;
|
||||
extern gpio_evaluatedSwitch sw_gpio_25;
|
||||
extern gpio_evaluatedSwitch sw_gpio_26;
|
||||
extern gpio_evaluatedSwitch sw_gpio_14;
|
||||
|
||||
//--- switches connected to 4-sw-to-analog stripboard ---
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_0;
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_1;
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_2;
|
||||
extern gpio_evaluatedSwitch sw_gpio_analog_3;
|
||||
|
||||
|
||||
//create global buzzer object
|
||||
extern buzzer_t buzzer;
|
390
main/guide-stepper.cpp
Normal file
@ -0,0 +1,390 @@
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
#include "freertos/queue.h"
|
||||
}
|
||||
|
||||
#include "stepper.hpp"
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
#include "guide-stepper.hpp"
|
||||
#include "encoder.hpp"
|
||||
#include "shutdown.hpp"
|
||||
|
||||
|
||||
//macro to get smaller value out of two
|
||||
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
|
||||
|
||||
//---------------------
|
||||
//--- configuration ---
|
||||
//---------------------
|
||||
//also see config.h
|
||||
//for pin definition
|
||||
|
||||
#define STEPPER_TEST_TRAVEL 65 // mm
|
||||
|
||||
#define MIN_MM 0 //TODO add feature so guide stays at zero for some steps (negative MIN_MM?), currently seems appropriate for even winding
|
||||
#define MAX_MM 95 //actual reel is 110, but currently guide turned out to stay at max position for too long
|
||||
#define POS_MAX_STEPS MAX_MM * STEPPER_STEPS_PER_MM
|
||||
#define POS_MIN_STEPS MIN_MM * STEPPER_STEPS_PER_MM
|
||||
|
||||
//tolerance added to last stored position at previous shutdown.
|
||||
//When calibrating at startup the stepper moves for that sum to get track of zero position (ensure crashes into hardware limit for at least some time)
|
||||
#define AUTO_HOME_TRAVEL_ADD_TO_LAST_POS_MM 20
|
||||
#define MAX_TOTAL_AXIS_TRAVEL_MM 103 //max possible travel distance, needed for auto-home
|
||||
|
||||
// speeds for testing with potentiometer (test task only)
|
||||
#define SPEED_MIN 2.0 // mm/s
|
||||
#define SPEED_MAX 70.0 // mm/s
|
||||
//note: actual speed is currently defined in config.h with STEPPER_SPEED_DEFAULT
|
||||
|
||||
#define LAYER_THICKNESS_MM 5 //height of one cable layer on reel -> increase in radius
|
||||
#define D_CABLE 6
|
||||
#define D_REEL 160
|
||||
#define PI 3.14159
|
||||
|
||||
|
||||
//simulate encoder with reset button to test stepper ctl task
|
||||
//note STEPPER_TEST has to be defined as well
|
||||
//#define STEPPER_SIMULATE_ENCODER
|
||||
|
||||
//----------------------
|
||||
//----- variables ------
|
||||
//----------------------
|
||||
typedef enum axisDirection_t {AXIS_MOVING_LEFT = 0, AXIS_MOVING_RIGHT} axisDirection_t;
|
||||
|
||||
static const char *TAG = "stepper-ctrl"; //tag for logging
|
||||
|
||||
static axisDirection_t currentAxisDirection = AXIS_MOVING_RIGHT;
|
||||
static uint32_t posNow = 0;
|
||||
|
||||
static int layerCount = 0;
|
||||
|
||||
// queue for sending commands to task handling guide movement
|
||||
static QueueHandle_t queue_commandsGuideTask;
|
||||
|
||||
|
||||
//----------------------
|
||||
//----- functions ------
|
||||
//----------------------
|
||||
|
||||
//=============================
|
||||
//=== guide_getAxisPosSteps ===
|
||||
//=============================
|
||||
// return local variable posNow
|
||||
// needed at shutdown detection to store last axis position in nvs
|
||||
int guide_getAxisPosSteps(){
|
||||
return posNow;
|
||||
}
|
||||
|
||||
|
||||
//==========================
|
||||
//==== guide_moveToZero ====
|
||||
//==========================
|
||||
//tell stepper-control task to move cable guide to zero position
|
||||
void guide_moveToZero(){
|
||||
bool valueToSend = true; // or false
|
||||
xQueueSend(queue_commandsGuideTask, &valueToSend, portMAX_DELAY);
|
||||
ESP_LOGI(TAG, "sending command to stepper_ctl task via queue");
|
||||
}
|
||||
|
||||
|
||||
//---------------------
|
||||
//---- travelSteps ----
|
||||
//---------------------
|
||||
//move axis certain Steps (relative) between left and right or reverse when negative
|
||||
void travelSteps(int stepsTarget){
|
||||
//TODO simplify this function, one simple calculation of new position?
|
||||
//with new custom driver no need to detect direction change
|
||||
|
||||
int stepsToGo, remaining;
|
||||
|
||||
stepsToGo = abs(stepsTarget);
|
||||
|
||||
// invert direction in reverse mode (cable gets spooled off reel)
|
||||
if (stepsTarget < 0) {
|
||||
currentAxisDirection = (currentAxisDirection == AXIS_MOVING_LEFT) ? AXIS_MOVING_RIGHT : AXIS_MOVING_LEFT; //toggle between RIGHT<->Left
|
||||
}
|
||||
|
||||
while (stepsToGo != 0){
|
||||
//--- currently moving right ---
|
||||
if (currentAxisDirection == AXIS_MOVING_RIGHT){ //currently moving right
|
||||
remaining = POS_MAX_STEPS - posNow; //calc remaining distance fom current position to limit
|
||||
if (stepsToGo > remaining){ //new distance will exceed limit
|
||||
stepper_setTargetPosSteps(POS_MAX_STEPS); //move to limit
|
||||
stepper_waitForStop(1000);
|
||||
posNow = POS_MAX_STEPS;
|
||||
currentAxisDirection = AXIS_MOVING_LEFT; //change current direction for next iteration
|
||||
//increment/decrement layer count depending on current cable direction
|
||||
layerCount += (stepsTarget > 0) - (stepsTarget < 0);
|
||||
if (layerCount < 0) layerCount = 0; //negative layers are not possible
|
||||
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
|
||||
stepper_setTargetPosSteps(posNow + stepsToGo); //move by (remaining) distance to reach target length
|
||||
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 if (currentAxisDirection == AXIS_MOVING_LEFT){
|
||||
remaining = posNow - POS_MIN_STEPS;
|
||||
if (stepsToGo > remaining){
|
||||
stepper_setTargetPosSteps(POS_MIN_STEPS);
|
||||
stepper_waitForStop(1000);
|
||||
posNow = POS_MIN_STEPS;
|
||||
currentAxisDirection = AXIS_MOVING_RIGHT; //switch direction
|
||||
//increment/decrement layer count depending on current cable direction
|
||||
layerCount += (stepsTarget > 0) - (stepsTarget < 0);
|
||||
if (layerCount < 0) layerCount = 0; //negative layers are not possible
|
||||
stepsToGo = stepsToGo - remaining;
|
||||
ESP_LOGI(TAG, " --- moved to min -> change direction (R) --- \n ");
|
||||
}
|
||||
else {
|
||||
stepper_setTargetPosSteps(posNow - stepsToGo); //when moving left the coordinate has to be decreased
|
||||
ESP_LOGD(TAG, "moving to %d\n", posNow - stepsToGo);
|
||||
posNow -= stepsToGo;
|
||||
stepsToGo = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// undo inversion of currentAxisDirection after reverse mode is finished
|
||||
if (stepsTarget < 0) {
|
||||
currentAxisDirection = (currentAxisDirection == AXIS_MOVING_LEFT) ? AXIS_MOVING_RIGHT : AXIS_MOVING_LEFT; //toggle between RIGHT<->Left
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
//------------------
|
||||
//---- travelMm ----
|
||||
//------------------
|
||||
//move axis certain Mm (relative) between left and right or reverse when negative
|
||||
void travelMm(int length){
|
||||
travelSteps(length * STEPPER_STEPS_PER_MM);
|
||||
}
|
||||
|
||||
|
||||
//----------------------
|
||||
//---- init_stepper ----
|
||||
//----------------------
|
||||
//initialize/configure stepper instance
|
||||
void init_stepper() {
|
||||
//TODO unnecessary wrapper?
|
||||
ESP_LOGW(TAG, "initializing stepper...");
|
||||
stepper_init();
|
||||
// create queue for sending commands to task handling guide movement
|
||||
// currently length 1 and only one command possible, thus bool
|
||||
queue_commandsGuideTask = xQueueCreate(1, sizeof(bool));
|
||||
}
|
||||
|
||||
|
||||
//--------------------------
|
||||
//--- updateSpeedFromAdc ---
|
||||
//--------------------------
|
||||
//function that updates speed value using ADC input and configured MIN/MAX - used for testing only
|
||||
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;
|
||||
stepper_setSpeed(speed);
|
||||
ESP_LOGW(TAG, "poti: %d (%.2lf%%), set speed to: %d", potiRead, poti*100, speed);
|
||||
}
|
||||
|
||||
|
||||
|
||||
//============================
|
||||
//==== TASK stepper_test =====
|
||||
//============================
|
||||
//test axis without using encoder input
|
||||
#ifndef STEPPER_SIMULATE_ENCODER
|
||||
void task_stepper_test(void *pvParameter)
|
||||
{
|
||||
stepper_init();
|
||||
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();
|
||||
|
||||
#ifdef ONE_BUTTON_TEST //test with "reset-button" only
|
||||
static int state = 0;
|
||||
//cycle through test commands with one button
|
||||
if (SW_RESET.risingEdge) {
|
||||
switch (state){
|
||||
case 0:
|
||||
stepper_setTargetPosMm(50);
|
||||
//stepper_setTargetPosSteps(1000);
|
||||
state++;
|
||||
break;
|
||||
case 1:
|
||||
stepper_setTargetPosMm(80);
|
||||
//stepper_setTargetPosSteps(100);
|
||||
state++;
|
||||
break;
|
||||
case 2:
|
||||
stepper_setTargetPosMm(20);
|
||||
//stepper_setTargetPosSteps(100);
|
||||
state++;
|
||||
break;
|
||||
case 3:
|
||||
stepper_setTargetPosMm(60);
|
||||
//stepper_setTargetPosSteps(2000);
|
||||
state = 0;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#else //test with all buttons
|
||||
if (SW_RESET.risingEdge) {
|
||||
buzzer.beep(1, 500, 100);
|
||||
stepper_setTargetPosMm(0);
|
||||
}
|
||||
if (SW_PRESET1.risingEdge) {
|
||||
buzzer.beep(1, 200, 100);
|
||||
stepper_setTargetPosMm(50);
|
||||
}
|
||||
if (SW_PRESET2.risingEdge) {
|
||||
buzzer.beep(2, 200, 100);
|
||||
stepper_setTargetPosMm(75);
|
||||
}
|
||||
if (SW_PRESET3.risingEdge) {
|
||||
buzzer.beep(3, 200, 100);
|
||||
stepper_setTargetPosMm(100);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif //end SIMULATE_ENCODER
|
||||
|
||||
|
||||
|
||||
//============================
|
||||
//===== TASK stepper_ctl =====
|
||||
//============================
|
||||
//task controlling the linear axis guiding the cable according to wire length spooled
|
||||
#ifdef STEPPER_SIMULATE_ENCODER
|
||||
void task_stepper_test(void *pvParameter)
|
||||
#else
|
||||
void task_stepper_ctl(void *pvParameter)
|
||||
#endif
|
||||
{
|
||||
//-- variables --
|
||||
static int encStepsPrev = 0; //measured encoder steps at last run
|
||||
static double travelStepsPartial = 0; //store resulted remaining partial steps last run
|
||||
|
||||
//temporary variables for calculating required steps, or logging
|
||||
int encStepsNow = 0; //get curretly measured steps of encoder
|
||||
int encStepsDelta = 0; //encoder steps changed since last iteration
|
||||
|
||||
double cableLen = 0;
|
||||
double travelStepsExact = 0; //steps axis has to travel
|
||||
int travelStepsFull = 0;
|
||||
double travelMm = 0;
|
||||
double turns = 0;
|
||||
float currentDiameter;
|
||||
|
||||
|
||||
|
||||
//initialize stepper at task start
|
||||
init_stepper();
|
||||
//define zero-position
|
||||
// use last known position stored at last shutdown to reduce time crashing into hardware limit
|
||||
int posLastShutdown = nvsReadLastAxisPosSteps();
|
||||
if (posLastShutdown >= 0)
|
||||
{ // would be -1 when failed
|
||||
ESP_LOGW(TAG, "auto-home: considerting pos last shutdown %dmm + tolerance %dmm",
|
||||
posLastShutdown / STEPPER_STEPS_PER_MM,
|
||||
AUTO_HOME_TRAVEL_ADD_TO_LAST_POS_MM);
|
||||
// home considering last position and offset, but limit to max distance possible
|
||||
stepper_home(MIN((posLastShutdown/STEPPER_STEPS_PER_MM + AUTO_HOME_TRAVEL_ADD_TO_LAST_POS_MM), MAX_TOTAL_AXIS_TRAVEL_MM));
|
||||
}
|
||||
else { // default to max travel when read from nvs failed
|
||||
stepper_home(MAX_TOTAL_AXIS_TRAVEL_MM);
|
||||
}
|
||||
|
||||
//repeatedly read changes in measured cable length and move axis accordingly
|
||||
while(1){
|
||||
#ifdef STEPPER_SIMULATE_ENCODER
|
||||
//TESTING - simulate encoder using switch
|
||||
SW_RESET.handle();
|
||||
//note
|
||||
if (SW_RESET.risingEdge) encStepsNow += 500;
|
||||
#else
|
||||
//get current length
|
||||
encStepsNow = encoder_getSteps();
|
||||
#endif
|
||||
|
||||
// move to zero and reset if command received via queue
|
||||
bool receivedValue;
|
||||
if (xQueueReceive(queue_commandsGuideTask, &receivedValue, 0) == pdTRUE)
|
||||
{
|
||||
// Process the received value
|
||||
// TODO support other commands (currently only move to zero possible)
|
||||
ESP_LOGW(TAG, "task: move-to-zero command received via queue, starting move, waiting until position reached");
|
||||
stepper_setTargetPosMm(0);
|
||||
stepper_waitForStop();
|
||||
//reset variables -> start tracking cable movement starting from position zero
|
||||
// ensure stepsDelta is 0
|
||||
encStepsNow = encoder_getSteps();
|
||||
encStepsPrev = encStepsNow;
|
||||
travelStepsPartial = 0;
|
||||
// set locally stored axis position and counted layers to 0 (used for calculating the target axis coordinate and steps)
|
||||
posNow = 0;
|
||||
layerCount = 0;
|
||||
currentAxisDirection = AXIS_MOVING_RIGHT;
|
||||
ESP_LOGW(TAG, "at position 0, reset variables, resuming normal cable guiding operation");
|
||||
}
|
||||
|
||||
//calculate change
|
||||
encStepsDelta = encStepsNow - encStepsPrev;
|
||||
//check if reset happend without moving to zero before - resulting in huge diff
|
||||
if (encStepsDelta != 0 && encStepsNow == 0){ // this should not happen and causes weird movement
|
||||
ESP_LOGE(TAG, "encoder steps changed to 0 (reset) without previous moveToZero() call, resulting in stepsDelta=%d", encStepsDelta);
|
||||
}
|
||||
|
||||
//read potentiometer and normalize (0-1) to get a variable for testing
|
||||
//float 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;
|
||||
//effective diameter increases each layer
|
||||
currentDiameter = D_REEL + LAYER_THICKNESS_MM * 2 * layerCount;
|
||||
turns = cableLen / (PI * currentDiameter);
|
||||
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 full step
|
||||
if (abs(travelStepsFull) > 1){
|
||||
travelStepsPartial = fmod(travelStepsExact, 1); //save remaining partial steps to be added in the next iteration
|
||||
ESP_LOGI(TAG, "dCablelen=%.2lf, dTurns=%.2lf, travelMm=%.3lf, StepsExact: %.3lf, StepsFull=%d, StepsPartial=%.3lf, totalLayerCount=%d, diameter=%.1f", cableLen, turns, travelMm, travelStepsExact, travelStepsFull, travelStepsPartial, layerCount, currentDiameter);
|
||||
ESP_LOGD(TAG, "MOVING %d steps", travelStepsFull);
|
||||
travelSteps(travelStepsExact);
|
||||
encStepsPrev = encStepsNow; //update previous length
|
||||
}
|
||||
else {
|
||||
//TODO use encoder queue to only run this check at encoder event?
|
||||
vTaskDelay(5);
|
||||
}
|
||||
vTaskDelay(5 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
20
main/guide-stepper.hpp
Normal file
@ -0,0 +1,20 @@
|
||||
#pragma once
|
||||
|
||||
//task that initializes and controls the stepper motor
|
||||
//current functionality:
|
||||
// - automatically auto-homes
|
||||
// - moves left and right repeatedly
|
||||
// - updates speed from potentiometer each cycle
|
||||
void task_stepper_test(void *pvParameter);
|
||||
|
||||
//task that initializes and controls the stepper motor
|
||||
// - moves stepper according to encoder movement
|
||||
void task_stepper_ctl(void *pvParameter);
|
||||
|
||||
|
||||
//tell stepper-control task to move cable guide to zero position
|
||||
void guide_moveToZero();
|
||||
|
||||
// return local variable posNow that stores the current position of cable guide axis in steps
|
||||
// needed by shutdown to store last axis position in nvs
|
||||
int guide_getAxisPosSteps();
|
@ -8,26 +8,38 @@ extern "C"
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
|
||||
}
|
||||
|
||||
#include "config.hpp"
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
#include "control.hpp"
|
||||
#include "buzzer.hpp"
|
||||
#include "switchesAnalog.hpp"
|
||||
#include "guide-stepper.hpp"
|
||||
#include "encoder.hpp"
|
||||
#include "shutdown.hpp"
|
||||
|
||||
#include "stepper.hpp"
|
||||
|
||||
|
||||
//=================================
|
||||
//=========== functions ===========
|
||||
//=================================
|
||||
|
||||
//------------------------
|
||||
//--- configure output ---
|
||||
//function to configure gpio pin as output
|
||||
//------------------------
|
||||
//configure a gpio pin as output
|
||||
void gpio_configure_output(gpio_num_t gpio_pin){
|
||||
gpio_pad_select_gpio(gpio_pin);
|
||||
gpio_set_direction(gpio_pin, GPIO_MODE_OUTPUT);
|
||||
}
|
||||
|
||||
|
||||
//--- init gpios ---
|
||||
//--------------------
|
||||
//---- init gpios ----
|
||||
//--------------------
|
||||
void init_gpios(){
|
||||
//--- outputs ---
|
||||
//4x stepper mosfets
|
||||
@ -49,6 +61,8 @@ void init_gpios(){
|
||||
//initialize and configure ADC
|
||||
adc1_config_width(ADC_WIDTH_BIT_12); //=> max resolution 4096
|
||||
adc1_config_channel_atten(ADC_CHANNEL_POTI, ADC_ATTEN_DB_11); //max voltage
|
||||
|
||||
adc1_config_channel_atten(ADC_CHANNEL_SUPPLY_VOLTAGE, ADC_ATTEN_DB_11); //max voltage
|
||||
}
|
||||
|
||||
|
||||
@ -70,20 +84,43 @@ void task_buzzer( void * pvParameters ){
|
||||
//======================================
|
||||
extern "C" void app_main()
|
||||
{
|
||||
//init outputs
|
||||
//init outputs and adc
|
||||
init_gpios();
|
||||
|
||||
//enable 5V volate regulator
|
||||
//enable 5V volage regulator (needed for display)
|
||||
gpio_set_level(GPIO_NUM_17, 1);
|
||||
|
||||
//init encoder (global)
|
||||
encoder_queue = encoder_init();
|
||||
|
||||
//define loglevel
|
||||
esp_log_level_set("*", ESP_LOG_INFO);
|
||||
esp_log_level_set("*", ESP_LOG_INFO); //default loglevel
|
||||
esp_log_level_set("buzzer", ESP_LOG_ERROR);
|
||||
esp_log_level_set("switches-analog", ESP_LOG_WARN);
|
||||
esp_log_level_set("control", ESP_LOG_INFO);
|
||||
esp_log_level_set("stepper-driver", ESP_LOG_WARN);
|
||||
esp_log_level_set("stepper-ctrl", ESP_LOG_WARN);
|
||||
esp_log_level_set("Dendostepper", ESP_LOG_WARN); //stepper lib
|
||||
esp_log_level_set("calc", ESP_LOG_WARN); //stepper lib
|
||||
esp_log_level_set("lowVoltage", ESP_LOG_INFO);
|
||||
|
||||
#ifdef STEPPER_TEST
|
||||
//create task for testing the stepper motor
|
||||
xTaskCreate(task_stepper_test, "task_stepper_test", configMINIMAL_STACK_SIZE * 3, NULL, 2, NULL);
|
||||
//xTaskCreate(task_stepper_debug, "task_stepper_test", configMINIMAL_STACK_SIZE * 3, NULL, 2, NULL);
|
||||
#else
|
||||
//create task for detecting power-off
|
||||
xTaskCreate(&task_shutDownDetection, "task_shutdownDet", 2048, NULL, 2, NULL);
|
||||
// wait for nvs to be initialized in shutDownDetection task
|
||||
vTaskDelay(50 / portTICK_PERIOD_MS);
|
||||
|
||||
//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, 4, NULL);
|
||||
|
||||
//create task for controlling the stepper motor (linear axis that guids the cable)
|
||||
xTaskCreate(task_stepper_ctl, "task_stepper_ctl", configMINIMAL_STACK_SIZE * 3, NULL, 2, NULL);
|
||||
#endif
|
||||
|
||||
//create task for handling the buzzer
|
||||
xTaskCreate(&task_buzzer, "task_buzzer", 2048, NULL, 2, NULL);
|
||||
|
||||
|
120
main/shutdown.cpp
Normal file
@ -0,0 +1,120 @@
|
||||
extern "C"
|
||||
{
|
||||
#include <stdio.h>
|
||||
#include <freertos/FreeRTOS.h>
|
||||
#include <freertos/task.h>
|
||||
#include "esp_system.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/adc.h"
|
||||
#include "nvs_flash.h"
|
||||
#include "nvs.h"
|
||||
}
|
||||
|
||||
#include "config.h"
|
||||
#include "shutdown.hpp"
|
||||
|
||||
#include "guide-stepper.hpp"
|
||||
|
||||
#define ADC_LOW_VOLTAGE_THRESHOLD 3200 // adc value where shut down is detected (store certain values before complete power loss)
|
||||
|
||||
static const char *TAG = "lowVoltage"; // tag for logging
|
||||
nvs_handle_t nvsHandle; // access nvs that was opened once, in any function
|
||||
|
||||
|
||||
|
||||
// store a u32 value in nvs as "lastPosSteps"
|
||||
void nvsWriteLastAxisPos(uint32_t value)
|
||||
{
|
||||
// update nvs value
|
||||
esp_err_t err = nvs_set_u32(nvsHandle, "lastPosSteps", value);
|
||||
if (err != ESP_OK)
|
||||
ESP_LOGE(TAG, "nvs: failed writing");
|
||||
err = nvs_commit(nvsHandle);
|
||||
if (err != ESP_OK)
|
||||
ESP_LOGE(TAG, "nvs: failed committing updates");
|
||||
else
|
||||
ESP_LOGI(TAG, "nvs: successfully committed updates");
|
||||
ESP_LOGW(TAG, "updated value in nvs to %d", value);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// read "lastPosSteps" from nvs, returns -1 if failed
|
||||
int nvsReadLastAxisPosSteps()
|
||||
{
|
||||
uint32_t valueRead;
|
||||
esp_err_t err = nvs_get_u32(nvsHandle, "lastPosSteps", &valueRead);
|
||||
switch (err)
|
||||
{
|
||||
case ESP_OK:
|
||||
ESP_LOGW(TAG, "Successfully read value %d from nvs", valueRead);
|
||||
return valueRead;
|
||||
break;
|
||||
case ESP_ERR_NVS_NOT_FOUND:
|
||||
ESP_LOGE(TAG, "nvs: the value '%s' is not initialized yet", "lastPosSteps");
|
||||
return -1;
|
||||
break;
|
||||
default:
|
||||
ESP_LOGE(TAG, "Error (%s) reading nvs!", esp_err_to_name(err));
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
// task that repeatedly checks supply voltage (12V) and saves certain values to nvs in case of power off detected
|
||||
// note: with the 2200uF capacitor in the 12V supply and measuring if 12V start do drop here, there is more than enough time to take action until the 3v3 regulator turns off
|
||||
void task_shutDownDetection(void *pvParameter)
|
||||
{
|
||||
//--- Initialize NVS ---
|
||||
ESP_LOGW(TAG, "initializing nvs...");
|
||||
esp_err_t err = nvs_flash_init();
|
||||
if (err == ESP_ERR_NVS_NO_FREE_PAGES || err == ESP_ERR_NVS_NEW_VERSION_FOUND)
|
||||
{
|
||||
ESP_LOGE(TAG, "NVS truncated -> deleting flash");
|
||||
// Retry nvs_flash_init
|
||||
ESP_ERROR_CHECK(nvs_flash_erase());
|
||||
err = nvs_flash_init();
|
||||
}
|
||||
|
||||
//--- open nvs-flash ---
|
||||
ESP_LOGW(TAG, "opening NVS-handle...");
|
||||
// create handle available for all functions in this file
|
||||
err = nvs_open("storage", NVS_READWRITE, &nvsHandle);
|
||||
if (err != ESP_OK)
|
||||
ESP_LOGE(TAG, "Error (%s) opening NVS handle!\n", esp_err_to_name(err));
|
||||
|
||||
// read stored value (returns 0 if unitialized/failed)
|
||||
//int lastPosSteps = nvsReadLastAxisPosSteps();
|
||||
//ESP_LOGW(TAG, "=> read value %d from nvs (stored at last shutdown)", lastPosSteps);
|
||||
|
||||
// repeatedly read ADC and check if below low voltage threshold
|
||||
bool voltageBelowThreshold = false;
|
||||
while (1) //TODO limit save frequency in case voltage repeadedly varys between threshold for some reason (e.g. offset drift)
|
||||
{
|
||||
// read adc
|
||||
int adc_reading = adc1_get_raw(ADC_CHANNEL_SUPPLY_VOLTAGE);
|
||||
|
||||
// evaulate threshold
|
||||
if (adc_reading < ADC_LOW_VOLTAGE_THRESHOLD) // below threshold => POWER SHUTDOWN DETECTED
|
||||
{
|
||||
// write to nvs and log once at change to below
|
||||
if (!voltageBelowThreshold){
|
||||
nvsWriteLastAxisPos(guide_getAxisPosSteps());
|
||||
ESP_LOGE(TAG, "voltage now below threshold! now=%d threshold=%d -> wrote last axis-pos to nvs", adc_reading, ADC_LOW_VOLTAGE_THRESHOLD);
|
||||
voltageBelowThreshold = true;
|
||||
}
|
||||
}
|
||||
else if (voltageBelowThreshold) // above threshold and previously below
|
||||
{
|
||||
// log at change to above
|
||||
ESP_LOGE(TAG, "voltage above threshold again: %d > %d - issue with power supply, or too threshold too high?", adc_reading, ADC_LOW_VOLTAGE_THRESHOLD);
|
||||
voltageBelowThreshold = false;
|
||||
}
|
||||
|
||||
// always log for debugging/calibrating
|
||||
ESP_LOGD(TAG, "read adc battery voltage: %d", adc_reading);
|
||||
|
||||
vTaskDelay(30 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
7
main/shutdown.hpp
Normal file
@ -0,0 +1,7 @@
|
||||
|
||||
// task that repeatedly checks supply voltage (12V) and saves certain values to nvs in case of it drops below a certain threshold (power off detected)
|
||||
void task_shutDownDetection(void *pvParameter);
|
||||
|
||||
// read last axis position in steps from nvs
|
||||
// returns -1 when reading from nvs failed
|
||||
int nvsReadLastAxisPosSteps();
|
304
main/stepper.cpp
Normal file
@ -0,0 +1,304 @@
|
||||
//custom driver for stepper motor
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
#include "hal/timer_types.h"
|
||||
#include <cstdint>
|
||||
#include <inttypes.h>
|
||||
|
||||
extern "C" {
|
||||
#include "driver/timer.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "esp_log.h"
|
||||
}
|
||||
|
||||
|
||||
//=====================
|
||||
//=== configuration ===
|
||||
//=====================
|
||||
//used macros from config.h:
|
||||
//#define STEPPER_STEP_PIN GPIO_NUM_18 //mos1
|
||||
//#define STEPPER_DIR_PIN GPIO_NUM_16 //ST3
|
||||
|
||||
//#define STEPPER_STEPS_PER_MM 200/2 //steps/mm (steps-per-rot / slope)
|
||||
//#define STEPPER_SPEED_DEFAULT 20 //mm/s
|
||||
//#define STEPPER_SPEED_MIN 4 //mm/s - speed threshold at which stepper immediately starts/stops
|
||||
//#define STEPPER_ACCEL_INC 3 //steps/s increment per cycle
|
||||
//#define STEPPER_DECEL_INC 8 //steps/s decrement per cycle
|
||||
|
||||
#define TIMER_F 1000000ULL
|
||||
#define TICK_PER_S TIMER_S
|
||||
#define NS_TO_T_TICKS(x) (x)
|
||||
|
||||
|
||||
|
||||
//========================
|
||||
//=== global variables ===
|
||||
//========================
|
||||
static const char *TAG = "stepper-driver"; //tag for logging
|
||||
|
||||
bool direction = 1;
|
||||
bool directionTarget = 1;
|
||||
bool timerIsRunning = false;
|
||||
bool timer_isr(void *arg);
|
||||
|
||||
static timer_group_t timerGroup = TIMER_GROUP_0;
|
||||
static timer_idx_t timerIdx = TIMER_0;
|
||||
|
||||
//TODO the below variables can be moved to isr function once debug output is no longer needed
|
||||
static uint64_t posTarget = 0;
|
||||
static uint64_t posNow = 0;
|
||||
static uint64_t stepsToGo = 0;
|
||||
static uint32_t speedMin = STEPPER_SPEED_MIN * STEPPER_STEPS_PER_MM;
|
||||
static uint32_t speedNow = speedMin;
|
||||
static int debug = 0;
|
||||
static uint32_t speedTarget = STEPPER_SPEED_DEFAULT * STEPPER_STEPS_PER_MM;
|
||||
//TODO/NOTE increment actually has to be re-calculated every run to have linear accel (because also gets called faster/slower)
|
||||
static uint32_t decel_increment = STEPPER_DECEL_INC;
|
||||
static uint32_t accel_increment = STEPPER_ACCEL_INC;
|
||||
|
||||
|
||||
|
||||
//======================
|
||||
//===== DEBUG task =====
|
||||
//======================
|
||||
void task_stepper_debug(void *pvParameter){
|
||||
while (1){
|
||||
ESP_LOGI("stepper-DEBUG",
|
||||
"timer=%d "
|
||||
"dir=%d "
|
||||
"dirTarget=%d "
|
||||
"posTarget=%llu "
|
||||
"posNow=%llu "
|
||||
"stepsToGo=%llu "
|
||||
"speedNow=%u "
|
||||
"speedTarget=%u "
|
||||
"debug=%d ",
|
||||
|
||||
timerIsRunning,
|
||||
direction,
|
||||
directionTarget,
|
||||
posTarget,
|
||||
posNow,
|
||||
stepsToGo,
|
||||
speedNow,
|
||||
speedTarget,
|
||||
debug
|
||||
);
|
||||
|
||||
vTaskDelay(300 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//=====================
|
||||
//===== set speed =====
|
||||
//=====================
|
||||
void stepper_setSpeed(uint32_t speedMmPerS) {
|
||||
ESP_LOGI(TAG, "set target speed from %u to %u mm/s (%u steps/s)",
|
||||
speedTarget, speedMmPerS, speedMmPerS * STEPPER_STEPS_PER_MM);
|
||||
speedTarget = speedMmPerS * STEPPER_STEPS_PER_MM;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//==========================
|
||||
//== set target pos STEPS ==
|
||||
//==========================
|
||||
void stepper_setTargetPosSteps(uint64_t target_steps) {
|
||||
ESP_LOGI(TAG, "update target position from %llu to %llu steps (stepsNow: %llu", posTarget, target_steps, posNow);
|
||||
posTarget = target_steps;
|
||||
|
||||
// Check if the timer is currently paused
|
||||
if (!timerIsRunning){
|
||||
// If the timer is paused, start it again with the updated targetSteps
|
||||
timerIsRunning = true;
|
||||
ESP_LOGI(TAG, "starting timer");
|
||||
ESP_ERROR_CHECK(timer_set_alarm_value(timerGroup, timerIdx, 1000));
|
||||
//timer_set_counter_value(timerGroup, timerIdx, 1000);
|
||||
ESP_ERROR_CHECK(timer_start(timerGroup, timerIdx));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//=========================
|
||||
//=== set target pos MM ===
|
||||
//=========================
|
||||
void stepper_setTargetPosMm(uint32_t posMm){
|
||||
ESP_LOGI(TAG, "set target position to %u mm", posMm);
|
||||
stepper_setTargetPosSteps(posMm * STEPPER_STEPS_PER_MM);
|
||||
}
|
||||
|
||||
|
||||
|
||||
//=======================
|
||||
//===== waitForStop =====
|
||||
//=======================
|
||||
//delay until stepper is stopped, optional timeout in ms, 0 = no limit
|
||||
void stepper_waitForStop(uint32_t timeoutMs){
|
||||
ESP_LOGI(TAG, "waiting for stepper to stop...");
|
||||
uint32_t timestampStart = esp_log_timestamp();
|
||||
while (timerIsRunning) {
|
||||
if ( (esp_log_timestamp() - timestampStart) >= timeoutMs && timeoutMs != 0){
|
||||
ESP_LOGE(TAG, "timeout waiting for stepper to stop");
|
||||
return;
|
||||
}
|
||||
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||
}
|
||||
ESP_LOGI(TAG, "finished waiting stepper to stop");
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//======================
|
||||
//======== home ========
|
||||
//======================
|
||||
//define zero/start position
|
||||
//run to limit and define zero/start position.
|
||||
//Currently simply runs stepper for travelMm and bumps into hardware limit
|
||||
void stepper_home(uint32_t travelMm){
|
||||
//TODO add timeout, limitswitch...
|
||||
ESP_LOGW(TAG, "initiate auto-home, moving %d mm...", travelMm);
|
||||
posNow = travelMm * STEPPER_STEPS_PER_MM;
|
||||
while (posNow != 0){
|
||||
//reactivate just in case stopped by other call to prevent deadlock
|
||||
if (!timerIsRunning) {
|
||||
stepper_setTargetPosSteps(0);
|
||||
}
|
||||
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||
}
|
||||
ESP_LOGW(TAG, "finished auto-home");
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//========================
|
||||
//===== init stepper =====
|
||||
//========================
|
||||
void stepper_init(){
|
||||
ESP_LOGI(TAG, "init - configure struct...");
|
||||
|
||||
// Configure pulse and direction pins as outputs
|
||||
ESP_LOGI(TAG, "init - configure gpio pins...");
|
||||
gpio_set_direction(STEPPER_DIR_PIN, GPIO_MODE_OUTPUT);
|
||||
gpio_set_direction(STEPPER_STEP_PIN, GPIO_MODE_OUTPUT);
|
||||
|
||||
ESP_LOGI(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(timerGroup, timerIdx, &timer_conf)); // init the timer
|
||||
ESP_ERROR_CHECK(timer_set_counter_value(timerGroup, timerIdx, 0)); // set it to 0
|
||||
ESP_ERROR_CHECK(timer_isr_callback_add(timerGroup, timerIdx, timer_isr, (void *)timerIdx, 0));
|
||||
}
|
||||
|
||||
|
||||
|
||||
//================================
|
||||
//=== timer interrupt function ===
|
||||
//================================
|
||||
bool timer_isr(void *arg) {
|
||||
|
||||
//-----------------
|
||||
//--- variables ---
|
||||
//-----------------
|
||||
//TODO used (currently global) variables here
|
||||
|
||||
//-----------------------------------
|
||||
//--- define direction, stepsToGo ---
|
||||
//-----------------------------------
|
||||
//Note: the idea is that the stepper has to decelerate to min speed first before changeing the direction
|
||||
//define target direction depending on position difference
|
||||
bool directionTarget = posTarget > posNow ? 1 : 0;
|
||||
//DIRECTION DIFFERS (change)
|
||||
if ( (direction != directionTarget) && (posTarget != posNow)) {
|
||||
if (stepsToGo == 0){ //standstill
|
||||
direction = directionTarget; //switch direction
|
||||
gpio_set_level(STEPPER_DIR_PIN, direction);
|
||||
stepsToGo = abs(int64_t(posTarget - posNow));
|
||||
} else {
|
||||
//set to minimun decel steps
|
||||
stepsToGo = (speedNow - speedMin) / decel_increment;
|
||||
}
|
||||
}
|
||||
//NORMAL (any direction 0/1)
|
||||
else {
|
||||
stepsToGo = abs(int64_t(posTarget - posNow));
|
||||
}
|
||||
|
||||
//--------------------
|
||||
//--- define speed ---
|
||||
//--------------------
|
||||
//FIXME noticed crash: division by 0 when min speed > target speed
|
||||
uint64_t stepsDecelRemaining = (speedNow - speedMin) / decel_increment;
|
||||
//DECELERATE
|
||||
|
||||
//prevent hard stop (faster stop than decel ramp)
|
||||
//Idea: when target gets lowered while decelerating,
|
||||
// move further than target to not exceed decel ramp (overshoot),
|
||||
// then change dir and move back to actual target pos
|
||||
if (stepsToGo < stepsDecelRemaining/2){ //significantly less steps planned to comply with decel ramp
|
||||
stepsToGo = stepsDecelRemaining; //set to required steps
|
||||
}
|
||||
|
||||
if (stepsToGo <= stepsDecelRemaining) {
|
||||
if ((speedNow - speedMin) > decel_increment) {
|
||||
speedNow -= decel_increment;
|
||||
} else {
|
||||
speedNow = speedMin; //PAUSE HERE??? / irrelevant?
|
||||
}
|
||||
}
|
||||
//ACCELERATE
|
||||
else if (speedNow < speedTarget) {
|
||||
speedNow += accel_increment;
|
||||
if (speedNow > speedTarget) speedNow = speedTarget;
|
||||
}
|
||||
//COASTING
|
||||
else { //not relevant?
|
||||
speedNow = speedTarget;
|
||||
}
|
||||
|
||||
//-------------------------------
|
||||
//--- update timer, increment ---
|
||||
//-------------------------------
|
||||
//AT TARGET -> STOP
|
||||
if (stepsToGo == 0) {
|
||||
timer_pause(timerGroup, timerIdx);
|
||||
timerIsRunning = false;
|
||||
speedNow = speedMin;
|
||||
return 1;
|
||||
}
|
||||
|
||||
//STEPS REMAINING -> NEXT STEP
|
||||
//update timer with new speed
|
||||
ESP_ERROR_CHECK(timer_set_alarm_value(timerGroup, timerIdx, TIMER_F / speedNow));
|
||||
|
||||
//generate pulse
|
||||
GPIO.out_w1ts = (1ULL << STEPPER_STEP_PIN); //turn on (fast)
|
||||
ets_delay_us(10);
|
||||
GPIO.out_w1tc = (1ULL << STEPPER_STEP_PIN); //turn off (fast)
|
||||
|
||||
//increment pos
|
||||
stepsToGo --;
|
||||
if (direction == 1){
|
||||
posNow ++;
|
||||
} else {
|
||||
//prevent underflow FIXME this case should not happen in the first place?
|
||||
if (posNow != 0){
|
||||
posNow --;
|
||||
} else {
|
||||
ESP_LOGE(TAG,"isr: posNow would be negative - ignoring decrement");
|
||||
}
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
25
main/stepper.hpp
Normal file
@ -0,0 +1,25 @@
|
||||
#pragma once
|
||||
|
||||
//init stepper pins and timer
|
||||
void stepper_init();
|
||||
|
||||
//delay until stepper is stopped, optional timeout in ms, 0 = no limit
|
||||
void stepper_waitForStop(uint32_t timeoutMs = 0);
|
||||
|
||||
//run to limit and define zero/start position. (busy until finished)
|
||||
//Currently simply runs stepper for travelMm and bumps into hardware limit
|
||||
void stepper_home(uint32_t travelMm = 60);
|
||||
|
||||
//set absolute target position in steps
|
||||
void stepper_setTargetPosSteps(uint64_t steps);
|
||||
|
||||
//set absolute target position in millimeters
|
||||
void stepper_setTargetPosMm(uint32_t posMm);
|
||||
|
||||
//set target speed in millimeters per second
|
||||
void stepper_setSpeed(uint32_t speedMmPerS);
|
||||
|
||||
|
||||
|
||||
//task that periodically logs variables for debugging stepper driver
|
||||
void task_stepper_debug(void *pvParameter);
|
@ -1,4 +1,6 @@
|
||||
#include "switchesAnalog.hpp"
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
|
||||
#define CHECK_BIT(var,pos) (((var)>>(pos)) & 1) //TODO duplicate code: same macro already used in vfd.cpp
|
||||
|
||||
|
@ -8,7 +8,6 @@ extern "C"
|
||||
#include <math.h>
|
||||
}
|
||||
|
||||
#include "config.hpp"
|
||||
#include "gpio_adc.hpp"
|
||||
|
||||
|
||||
|
@ -1,12 +1,14 @@
|
||||
#include "vfd.hpp"
|
||||
#include "config.h"
|
||||
#include "global.hpp"
|
||||
|
||||
#define CHECK_BIT(var,pos) (((var)>>(pos)) & 1)
|
||||
|
||||
const char* vfd_directionStr[2] = {"FWD", "REV"};
|
||||
static const char *TAG = "vfd";
|
||||
uint8_t level = 0; //current speed level
|
||||
bool state = false; //current state
|
||||
vfd_direction_t direction = FWD; //current direction
|
||||
static uint8_t level = 0; //current speed level
|
||||
static bool state = false; //current state
|
||||
static vfd_direction_t direction = FWD; //current direction
|
||||
|
||||
|
||||
//=============================
|
||||
|
@ -9,7 +9,6 @@ extern "C"
|
||||
#include "esp_log.h"
|
||||
}
|
||||
|
||||
#include "config.hpp"
|
||||
|
||||
//enum defining motor direction
|
||||
typedef enum vfd_direction_t {FWD, REV} vfd_direction_t;
|
||||
|
BIN
pcb/stepper-filter/filter_stripboard.ods
Normal file
75
pcb/stepper-filter/stepper-filter.kicad_prl
Normal file
@ -0,0 +1,75 @@
|
||||
{
|
||||
"board": {
|
||||
"active_layer": 0,
|
||||
"active_layer_preset": "",
|
||||
"auto_track_width": true,
|
||||
"hidden_nets": [],
|
||||
"high_contrast_mode": 0,
|
||||
"net_color_mode": 1,
|
||||
"opacity": {
|
||||
"pads": 1.0,
|
||||
"tracks": 1.0,
|
||||
"vias": 1.0,
|
||||
"zones": 0.6
|
||||
},
|
||||
"ratsnest_display_mode": 0,
|
||||
"selection_filter": {
|
||||
"dimensions": true,
|
||||
"footprints": true,
|
||||
"graphics": true,
|
||||
"keepouts": true,
|
||||
"lockedItems": true,
|
||||
"otherItems": true,
|
||||
"pads": true,
|
||||
"text": true,
|
||||
"tracks": true,
|
||||
"vias": true,
|
||||
"zones": true
|
||||
},
|
||||
"visible_items": [
|
||||
0,
|
||||
1,
|
||||
2,
|
||||
3,
|
||||
4,
|
||||
5,
|
||||
8,
|
||||
9,
|
||||
10,
|
||||
11,
|
||||
12,
|
||||
13,
|
||||
14,
|
||||
15,
|
||||
16,
|
||||
17,
|
||||
18,
|
||||
19,
|
||||
20,
|
||||
21,
|
||||
22,
|
||||
23,
|
||||
24,
|
||||
25,
|
||||
26,
|
||||
27,
|
||||
28,
|
||||
29,
|
||||
30,
|
||||
32,
|
||||
33,
|
||||
34,
|
||||
35,
|
||||
36
|
||||
],
|
||||
"visible_layers": "fffffff_ffffffff",
|
||||
"zone_display_mode": 0
|
||||
},
|
||||
"meta": {
|
||||
"filename": "stepper-filter.kicad_prl",
|
||||
"version": 3
|
||||
},
|
||||
"project": {
|
||||
"files": []
|
||||
}
|
||||
}
|
294
pcb/stepper-filter/stepper-filter.kicad_pro
Normal file
@ -0,0 +1,294 @@
|
||||
{
|
||||
"board": {
|
||||
"layer_presets": []
|
||||
},
|
||||
"boards": [],
|
||||
"cvpcb": {
|
||||
"equivalence_files": []
|
||||
},
|
||||
"erc": {
|
||||
"erc_exclusions": [],
|
||||
"meta": {
|
||||
"version": 0
|
||||
},
|
||||
"pin_map": [
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
1,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
1,
|
||||
2,
|
||||
1,
|
||||
1,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
0,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
1,
|
||||
2,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
0,
|
||||
2,
|
||||
1,
|
||||
1,
|
||||
0,
|
||||
0,
|
||||
1,
|
||||
0,
|
||||
2,
|
||||
0,
|
||||
0,
|
||||
2
|
||||
],
|
||||
[
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2
|
||||
]
|
||||
],
|
||||
"rule_severities": {
|
||||
"bus_definition_conflict": "error",
|
||||
"bus_entry_needed": "error",
|
||||
"bus_label_syntax": "error",
|
||||
"bus_to_bus_conflict": "error",
|
||||
"bus_to_net_conflict": "error",
|
||||
"different_unit_footprint": "error",
|
||||
"different_unit_net": "error",
|
||||
"duplicate_reference": "error",
|
||||
"duplicate_sheet_names": "error",
|
||||
"extra_units": "error",
|
||||
"global_label_dangling": "warning",
|
||||
"hier_label_mismatch": "error",
|
||||
"label_dangling": "error",
|
||||
"lib_symbol_issues": "warning",
|
||||
"multiple_net_names": "warning",
|
||||
"net_not_bus_member": "warning",
|
||||
"no_connect_connected": "warning",
|
||||
"no_connect_dangling": "warning",
|
||||
"pin_not_connected": "error",
|
||||
"pin_not_driven": "error",
|
||||
"pin_to_pin": "warning",
|
||||
"power_pin_not_driven": "error",
|
||||
"similar_labels": "warning",
|
||||
"unannotated": "error",
|
||||
"unit_value_mismatch": "error",
|
||||
"unresolved_variable": "error",
|
||||
"wire_dangling": "error"
|
||||
}
|
||||
},
|
||||
"libraries": {
|
||||
"pinned_footprint_libs": [],
|
||||
"pinned_symbol_libs": []
|
||||
},
|
||||
"meta": {
|
||||
"filename": "stepper-filter.kicad_pro",
|
||||
"version": 1
|
||||
},
|
||||
"net_settings": {
|
||||
"classes": [
|
||||
{
|
||||
"bus_width": 12.0,
|
||||
"clearance": 0.2,
|
||||
"diff_pair_gap": 0.25,
|
||||
"diff_pair_via_gap": 0.25,
|
||||
"diff_pair_width": 0.2,
|
||||
"line_style": 0,
|
||||
"microvia_diameter": 0.3,
|
||||
"microvia_drill": 0.1,
|
||||
"name": "Default",
|
||||
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||
"track_width": 0.25,
|
||||
"via_diameter": 0.8,
|
||||
"via_drill": 0.4,
|
||||
"wire_width": 6.0
|
||||
}
|
||||
],
|
||||
"meta": {
|
||||
"version": 2
|
||||
},
|
||||
"net_colors": null
|
||||
},
|
||||
"pcbnew": {
|
||||
"last_paths": {
|
||||
"gencad": "",
|
||||
"idf": "",
|
||||
"netlist": "",
|
||||
"specctra_dsn": "",
|
||||
"step": "",
|
||||
"vrml": ""
|
||||
},
|
||||
"page_layout_descr_file": ""
|
||||
},
|
||||
"schematic": {
|
||||
"annotate_start_num": 0,
|
||||
"drawing": {
|
||||
"default_line_thickness": 6.0,
|
||||
"default_text_size": 50.0,
|
||||
"field_names": [],
|
||||
"intersheets_ref_own_page": false,
|
||||
"intersheets_ref_prefix": "",
|
||||
"intersheets_ref_short": false,
|
||||
"intersheets_ref_show": false,
|
||||
"intersheets_ref_suffix": "",
|
||||
"junction_size_choice": 3,
|
||||
"label_size_ratio": 0.375,
|
||||
"pin_symbol_size": 25.0,
|
||||
"text_offset_ratio": 0.15
|
||||
},
|
||||
"legacy_lib_dir": "",
|
||||
"legacy_lib_list": [],
|
||||
"meta": {
|
||||
"version": 1
|
||||
},
|
||||
"net_format_name": "",
|
||||
"page_layout_descr_file": "",
|
||||
"plot_directory": "",
|
||||
"spice_adjust_passive_values": false,
|
||||
"spice_external_command": "spice \"%I\"",
|
||||
"subpart_first_id": 65,
|
||||
"subpart_id_separator": 0
|
||||
},
|
||||
"sheets": [
|
||||
[
|
||||
"0534e379-8bf0-4abf-a148-fc91b6440529",
|
||||
""
|
||||
]
|
||||
],
|
||||
"text_variables": {}
|
||||
}
|
1265
pcb/stepper-filter/stepper-filter.kicad_sch
Normal file
38
sdkconfig
@ -54,6 +54,7 @@ CONFIG_BOOTLOADER_LOG_LEVEL=3
|
||||
CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y
|
||||
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
||||
# CONFIG_BOOTLOADER_APP_TEST is not set
|
||||
CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y
|
||||
CONFIG_BOOTLOADER_WDT_ENABLE=y
|
||||
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
||||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||
@ -95,6 +96,9 @@ CONFIG_ESPTOOLPY_FLASHSIZE_2MB=y
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_4MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_8MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_16MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_32MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_64MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_128MB is not set
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE="2MB"
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y
|
||||
CONFIG_ESPTOOLPY_BEFORE_RESET=y
|
||||
@ -263,8 +267,8 @@ CONFIG_EFUSE_MAX_BLK_LEN=192
|
||||
#
|
||||
CONFIG_ESP_TLS_USING_MBEDTLS=y
|
||||
# CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set
|
||||
# CONFIG_ESP_TLS_SERVER is not set
|
||||
# CONFIG_ESP_TLS_CLIENT_SESSION_TICKETS is not set
|
||||
# CONFIG_ESP_TLS_SERVER is not set
|
||||
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
||||
# CONFIG_ESP_TLS_INSECURE is not set
|
||||
# end of ESP-TLS
|
||||
@ -416,10 +420,11 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
||||
#
|
||||
# Sleep Config
|
||||
#
|
||||
CONFIG_ESP_SLEEP_POWER_DOWN_FLASH=y
|
||||
# CONFIG_ESP_SLEEP_POWER_DOWN_FLASH is not set
|
||||
CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y
|
||||
# CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set
|
||||
# CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND is not set
|
||||
CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y
|
||||
# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set
|
||||
# end of Sleep Config
|
||||
|
||||
#
|
||||
@ -472,6 +477,13 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y
|
||||
# CONFIG_PM_ENABLE is not set
|
||||
# end of Power Management
|
||||
|
||||
#
|
||||
# ESP Ringbuf
|
||||
#
|
||||
# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set
|
||||
# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set
|
||||
# end of ESP Ringbuf
|
||||
|
||||
#
|
||||
# ESP System Settings
|
||||
#
|
||||
@ -555,6 +567,8 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y
|
||||
# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set
|
||||
# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set
|
||||
CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y
|
||||
# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set
|
||||
CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7
|
||||
# end of Wi-Fi
|
||||
|
||||
#
|
||||
@ -628,11 +642,7 @@ CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20
|
||||
CONFIG_FMB_CONTROLLER_STACK_SIZE=4096
|
||||
CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20
|
||||
# CONFIG_FMB_TIMER_PORT_ENABLED is not set
|
||||
CONFIG_FMB_TIMER_GROUP=0
|
||||
CONFIG_FMB_TIMER_INDEX=0
|
||||
CONFIG_FMB_MASTER_TIMER_GROUP=0
|
||||
CONFIG_FMB_MASTER_TIMER_INDEX=0
|
||||
# CONFIG_FMB_TIMER_ISR_IN_IRAM is not set
|
||||
# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set
|
||||
# end of Modbus configuration
|
||||
|
||||
#
|
||||
@ -791,6 +801,7 @@ CONFIG_LWIP_TCP_SYNMAXRTX=12
|
||||
CONFIG_LWIP_TCP_MSS=1440
|
||||
CONFIG_LWIP_TCP_TMR_INTERVAL=250
|
||||
CONFIG_LWIP_TCP_MSL=60000
|
||||
CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000
|
||||
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
|
||||
CONFIG_LWIP_TCP_WND_DEFAULT=5744
|
||||
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
||||
@ -901,6 +912,7 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
||||
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200
|
||||
# end of Certificate Bundle
|
||||
|
||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||
@ -1048,6 +1060,7 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
||||
#
|
||||
# NVS
|
||||
#
|
||||
# CONFIG_NVS_ASSERT_ERROR_CHECK is not set
|
||||
# end of NVS
|
||||
|
||||
#
|
||||
@ -1185,7 +1198,6 @@ CONFIG_VFS_SUPPORT_TERMIOS=y
|
||||
# Host File System I/O (Semihosting)
|
||||
#
|
||||
CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||
CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||
# end of Host File System I/O (Semihosting)
|
||||
# end of Virtual file system
|
||||
|
||||
@ -1202,6 +1214,7 @@ CONFIG_WL_SECTOR_SIZE=4096
|
||||
#
|
||||
CONFIG_WIFI_PROV_SCAN_MAX_ENTRIES=16
|
||||
CONFIG_WIFI_PROV_AUTOSTOP_TIMEOUT=30
|
||||
# CONFIG_WIFI_PROV_BLE_FORCE_ENCRYPTION is not set
|
||||
# end of Wi-Fi Provisioning Manager
|
||||
|
||||
#
|
||||
@ -1214,6 +1227,8 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y
|
||||
# CONFIG_WPA_TESTING_OPTIONS is not set
|
||||
# CONFIG_WPA_WPS_STRICT is not set
|
||||
# CONFIG_WPA_11KV_SUPPORT is not set
|
||||
# CONFIG_WPA_MBO_SUPPORT is not set
|
||||
# CONFIG_WPA_DPP_SUPPORT is not set
|
||||
# end of Supplicant
|
||||
# end of Component config
|
||||
|
||||
@ -1291,7 +1306,7 @@ CONFIG_POST_EVENTS_FROM_IRAM_ISR=y
|
||||
# CONFIG_TWO_UNIVERSAL_MAC_ADDRESS is not set
|
||||
CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y
|
||||
CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4
|
||||
CONFIG_ESP_SYSTEM_PD_FLASH=y
|
||||
# CONFIG_ESP_SYSTEM_PD_FLASH is not set
|
||||
# CONFIG_ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND is not set
|
||||
CONFIG_IPC_TASK_STACK_SIZE=1536
|
||||
CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y
|
||||
@ -1338,8 +1353,6 @@ CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20
|
||||
CONFIG_MB_CONTROLLER_STACK_SIZE=4096
|
||||
CONFIG_MB_EVENT_QUEUE_TIMEOUT=20
|
||||
# CONFIG_MB_TIMER_PORT_ENABLED is not set
|
||||
CONFIG_MB_TIMER_GROUP=0
|
||||
CONFIG_MB_TIMER_INDEX=0
|
||||
# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set
|
||||
CONFIG_TIMER_TASK_PRIORITY=1
|
||||
CONFIG_TIMER_TASK_STACK_DEPTH=2048
|
||||
@ -1382,5 +1395,4 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y
|
||||
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||
CONFIG_SUPPORT_TERMIOS=y
|
||||
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||
# End of deprecated options
|
||||
|
104
testing/cnc-guide/main.c
Normal file
@ -0,0 +1,104 @@
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <math.h>
|
||||
|
||||
#define MAX 100
|
||||
#define MIN 10
|
||||
#define TRAVEL MAX-MIN
|
||||
|
||||
|
||||
|
||||
//==== VARIABLES ====
|
||||
bool direction = true;
|
||||
uint16_t posNow = 10;
|
||||
|
||||
|
||||
|
||||
//==== FUNCTIONS ====
|
||||
|
||||
//print position
|
||||
//print line that illustrates the position pos between 0 and MAX
|
||||
//e.g. "|----<=>--------|"
|
||||
void printPos(int pos){
|
||||
int width = 50;
|
||||
printf("(%d)|", pos);
|
||||
for (int i = 0; i<(pos) * width/MAX; i++) printf("-");
|
||||
printf("<=>");
|
||||
for (int i = 0; i<(MAX-pos) * width/MAX; i++) printf("-");
|
||||
printf("|\n");
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
//move "virtual axis" to absolute coordinate in mm
|
||||
void moveToAbs(int d){
|
||||
int posOld = posNow;
|
||||
printf ("moving from %d %s to %d (%s)\n", posNow, direction ? "=>" : "<=", d, direction ? "RIGHT" : "LEFT");
|
||||
posNow = d;
|
||||
//illustrate movement (print position for each coordinate change)
|
||||
for (int i=posOld; i!=posNow; i+=posNow>posOld?1:-1) printPos(i);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
//travel back and forth between MIN and MAX coordinate for a certain distance
|
||||
//negative values are processed reversed
|
||||
void travel(int length){
|
||||
int d, remaining;
|
||||
d = abs(length);
|
||||
if(length < 0) direction = !direction; //invert direction in reverse mode
|
||||
|
||||
while (d != 0){
|
||||
//--- currently moving right ---
|
||||
if (direction == true){ //currently moving right
|
||||
remaining = MAX - posNow; //calc remaining distance fom current position to limit
|
||||
if (d > remaining){ //new distance will exceed limit
|
||||
moveToAbs (MAX); //move to limit
|
||||
direction = false; //change current direction for next iteration
|
||||
d = d - remaining; //decrease target length by already traveled distance
|
||||
printf(" --- changed direction (L) --- \n ");
|
||||
}
|
||||
else { //target distance does not reach the limit
|
||||
moveToAbs (posNow + d); //move by (remaining) distance to reach target length
|
||||
d = 0; //finished, reset target length (could as well exit loop/break)
|
||||
}
|
||||
}
|
||||
|
||||
//--- currently moving left ---
|
||||
else {
|
||||
remaining = posNow - MIN;
|
||||
if (d > remaining){
|
||||
moveToAbs (MIN);
|
||||
direction = true;
|
||||
d = d - remaining;
|
||||
printf(" --- changed direction (R) --- \n ");
|
||||
}
|
||||
else {
|
||||
moveToAbs (posNow - d); //when moving left the coordinate has to be decreased
|
||||
d = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if(length < 0) direction = !direction; //undo inversion of direction after reverse mode is finished
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
//==== MAIN ====
|
||||
int main (void)
|
||||
{
|
||||
int input;
|
||||
printf("**cable-length-cutter testing cnc-guide**\n");
|
||||
while(1){
|
||||
printf("enter mm to travel:");
|
||||
scanf("%d", &input);
|
||||
travel(input);
|
||||
printf("\n");
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
7
testing/cnc-guide/makefile
Normal file
@ -0,0 +1,7 @@
|
||||
default: program
|
||||
|
||||
program:
|
||||
gcc main.c -o a.out -lm
|
||||
|
||||
clean:
|
||||
-rm -f a.out
|