Merge remote-tracking branch 'firmware-local/main'

main
radex 2024-02-03 15:01:17 +01:00
commit fd6d199f98
Signed by: radex
SSH Key Fingerprint: SHA256:hvqRXAGG1h89yqnS+cyFTLKQbzjWD4uXIqw7Y+0ws30
7 changed files with 375 additions and 0 deletions

5
firmware/.gitignore vendored Normal file
View File

@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch

10
firmware/.vscode/extensions.json vendored Normal file
View File

@ -0,0 +1,10 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
}

39
firmware/include/README Normal file
View File

@ -0,0 +1,39 @@
This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.
```src/main.c
#include "header.h"
int main (void)
{
...
}
```
Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.
In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot.
Read more about using header files in official GCC documentation:
* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

46
firmware/lib/README Normal file
View File

@ -0,0 +1,46 @@
This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file.
The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]").
For example, see a structure of the following two libraries `Foo` and `Bar`:
|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c
and a contents of `src/main.c`:
```
#include <Foo.h>
#include <Bar.h>
int main (void)
{
...
}
```
PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files.
More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html

21
firmware/platformio.ini Normal file
View File

@ -0,0 +1,21 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[env:uno]
platform = atmelavr
board = uno
framework = arduino
monitor_speed = 115200
lib_deps =
SPI
TMCStepper
AccelStepper

243
firmware/src/main.cpp Normal file
View File

@ -0,0 +1,243 @@
#include <TMCStepper.h>
#define EN_PIN 7 // Enable
#define DIR_PIN 9 // Direction
#define STEP_PIN 8 // Step
#define DIAG_PIN 10 // Diagnostic
#define CS_PIN 42 // Chip select
#define SW_MOSI 66 // Software Master Out Slave In (MOSI)
#define SW_MISO 44 // Software Master In Slave Out (MISO)
#define SW_SCK 64 // Software Slave Clock (SCK)
#define SW_RX 5 // TMC2208/TMC2224 SoftwareSerial receive pin
#define SW_TX 5 // TMC2208/TMC2224 SoftwareSerial transmit pin
#define SERIAL_PORT Serial1 // TMC2208/TMC2224 HardwareSerial port
#define DRIVER_ADDRESS 0b00 // TMC2209 Driver address according to MS1 and MS2
#define R_SENSE 0.11f // Match to your driver
// SilentStepStick series use 0.11
// UltiMachine Einsy and Archim2 boards use 0.2
// Panucatt BSD2660 uses 0.1
// Watterott TMC5160 uses 0.075
TMC2209Stepper driver(SW_RX, SW_TX, R_SENSE, DRIVER_ADDRESS);
#define MICROSTEPS 2
#define STEPS_PER_REV 200 * MICROSTEPS
void setup() {
Serial.begin(115200);
Serial.println("Start...");
// give power supply time to settle
delay(1000);
pinMode(EN_PIN, OUTPUT);
pinMode(STEP_PIN, OUTPUT);
pinMode(DIR_PIN, OUTPUT);
pinMode(DIAG_PIN, INPUT);
digitalWrite(EN_PIN, LOW);
// Enable one according to your setup
//SPI.begin(); // SPI drivers
//SERIAL_PORT.begin(115200); // HW UART drivers
// driver.beginSerial(115200); // SW UART drivers
// driver.internal_Rsense(true);
driver.begin();
driver.push();
// TOFF General enable for the motor driver, the actual value does not influence StealthChop
driver.toff(4);
// RMS (mA) current for running, second arg - hold current multiplier
driver.rms_current(1800, 0.5);
driver.microsteps(0);
// Enable stealthChop
driver.en_spreadCycle(false);
// When using the UART interface, the configuration pin should be disabled via GCONF.pdn_disable = 1.
// Program IHOLD as desired for standstill periods.
driver.pdn_disable(true);
// driver.en_spreadCycle(true); // Toggle spreadCycle on TMC2208/2209/2224
// driver.hysteresis_start(8);
// driver.hysteresis_end(hysteresis_end);
// driver.blank_time(54);
// driver.toff(5);
// driver.freewheel(0b01);
// This is the lower threshold velocity for switching on smart energy CoolStep and StallGuard to DIAG output
// Set this parameter to disable CoolStep at low speeds, where it cannot work reliably.
// The stall output signal become enabled when exceeding this velocity. It becomes disabled again once the velocity falls below this threshold
// (TCOOLTHRS ≥ TSTEP > TPWMTHRS)
driver.TCOOLTHRS(0xFFFFF); // 20bit max
// The driver.SG_RESULT() returns the result in the legacy 10 bit format, where the first and the last bit are always set to 0.
// Dividing it by 2 gives us the value in the same range as driver.SGTHRS(STALL_VALUE);
// if the (converted) SG_RESULT <= 2 * SGTHRS, stall is reported
driver.SGTHRS(35);
// default value: SGTHRS / 16 + 1
// for sgResult = semin * 16, the current starts getting increased to resist the resistance
// the bigger it is, the bigger the chance the motor is going to react to adversity
// by increasing the current
// 0..15
driver.semin(15);
// SEMAX is used to determine when the extra current should be disabled.
// the higher it is, the harder it's going to be to go back to energy efficient mode
// 0 to 2 recommended
// 0..15
driver.semax(8);
// If the StallGuard4result is equal to or above (SEMIN+SEMAX+1)*32 the motro current becomes decreased to save energy
driver.sedn(0b01);
// driver.en_pwm_mode(true); // Toggle stealthChop on TMC2130/2160/5130/5160
// driver.pwm_autoscale(true); // Needed for stealthChop
Serial.print(F("\nTesting connection..."));
uint8_t result = driver.test_connection();
if (result) {
Serial.println(F("failed!"));
Serial.print(F("Likely cause: "));
switch(result) {
case 1: Serial.println(F("loose connection")); break;
case 2: Serial.println(F("Likely cause: no power")); break;
}
Serial.println(F("Fix the problem and reset board."));
delay(200);
abort();
}
Serial.println(F("OK"));
// stealthChop2 regulates to nominal current and stores result to PWM_OFS_AUTO (Requires stand still for >130ms)
delay(130);
}
bool shaft = false;
unsigned int stepsDelay = 10000;
bool shouldRun = true;
int stepsMade = 0;
int stallSigs = 0;
void loop() {
if (Serial.available()) {
char c = Serial.read();
if (c == 'r') {
shaft = !shaft;
driver.shaft(shaft);
Serial.println("Shaft reversed");
} else if (c == '+') {
stepsDelay *= 0.8;
if (stepsDelay < 10) {
stepsDelay = 10;
}
Serial.println("Speed: " + String(stepsDelay));
} else if (c == '-') {
stepsDelay *= 1.2;
Serial.println("Speed: " + String(stepsDelay));
} else if (c == 's') {
shouldRun = false;
Serial.println("Stopped.");
} else if (c == '0') {
shouldRun = false;
digitalWrite(EN_PIN, HIGH);
Serial.println("Stopped & disabled.");
} else if (c == 'g') {
shouldRun = true;
digitalWrite(EN_PIN, LOW);
Serial.println("Running.");
} else if (c == 't') {
// Serial.print("LOST_STEPS: 0b");
// Serial.println(driver.LOST_STEPS(), DEC);
Serial.print("PWM_SCALE: 0b");
Serial.println(driver.PWM_SCALE(), DEC);
Serial.print("SGTHRS: ");
Serial.println(driver.SGTHRS(), DEC);
Serial.print("SG_RESULT: ");
Serial.println(driver.SG_RESULT()/2, DEC);
Serial.print("GCONF: ");
Serial.println(driver.GCONF(), DEC);
Serial.print("CHOPCONF: 0b");
Serial.println(driver.CHOPCONF(), BIN);
}
// else if (c == 'h') {
// hysteresis_end = hysteresis_end + 1;
// if (hysteresis_end > 12) {
// hysteresis_end = -3;
// }
// driver.hysteresis_end(hysteresis_end);
// Serial.println("Hysteresis end: " + String(hysteresis_end));
// } else if (c == '8') {
// while (driver.cur_a() < 240) {
// digitalWrite(STEP_PIN, HIGH);
// digitalWrite(STEP_PIN, LOW);
// delayMicroseconds(3);
// }
// }
}
if (shouldRun) {
if (stepsMade >= STEPS_PER_REV) {
stepsMade = 0;
// shaft = !shaft;
// driver.shaft(shaft);
}
for (uint32_t i = 24; i>0; i--) {
digitalWrite(STEP_PIN, LOW);
delayMicroseconds(1);
digitalWrite(STEP_PIN, HIGH);
delayMicroseconds(1);
digitalWrite(STEP_PIN, LOW);
delayMicroseconds(1);
delayMicroseconds(stepsDelay);
if (digitalRead(DIAG_PIN) == HIGH) {
stallSigs += 1;
// Serial.println("");
// shouldRun = false;
}
}
stepsMade += 100;
if (stallSigs) {
Serial.print("STALLs ");
Serial.println(stallSigs, DEC);
if (stallSigs >= 3) {
Serial.print("Will reverse at");
Serial.println(driver.SG_RESULT()/2, DEC);
delay(200);
shaft = !shaft;
driver.shaft(shaft);
}
stallSigs = 0;
}
// Serial.println(driver.TCOOLTHRS(), DEC);
// Serial.println(driver.TSTEP(), DEC);
// Serial.println(driver.TPWMTHRS(), DEC);
// Serial.println();
// if (driver.SG_RESULT() > 105) {
// shaft = !shaft;
// driver.shaft(shaft);
// }
// Serial.print(driver.SG_RESULT()/2, DEC);
// Serial.print(" ");
// Serial.print(digitalRead(DIAG_PIN), DEC);
// // Serial.print(" ");
// // Serial.println(driver.cs2rms(driver.cs_actual()), DEC);
// Serial.println();
}
}

11
firmware/test/README Normal file
View File

@ -0,0 +1,11 @@
This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html