1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-08 21:30:54 +02:00

Made everything compile again.

This commit is contained in:
Stefan de Bruijn
2020-12-16 11:52:16 +01:00
parent 9bc65cf68e
commit 789e50544c
22 changed files with 252 additions and 245 deletions

View File

@@ -16,6 +16,7 @@ Global
EndGlobalSection
GlobalSection(ProjectConfigurationPlatforms) = postSolution
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x64.ActiveCfg = Debug|x64
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x64.Build.0 = Debug|x64
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x86.ActiveCfg = Debug|Win32
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x86.Build.0 = Debug|Win32
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x64.ActiveCfg = Release|x64
@@ -23,7 +24,6 @@ Global
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x86.ActiveCfg = Release|Win32
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x86.Build.0 = Release|Win32
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x64.ActiveCfg = Debug|x64
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x64.Build.0 = Debug|x64
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x86.ActiveCfg = Debug|Win32
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x86.Build.0 = Debug|Win32
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Release|x64.ActiveCfg = Release|x64

View File

@@ -35,47 +35,47 @@
#define TRINAMIC_HOMING_MODE TrinamicMode :: StealthChop
#define TMC_UART UART_NUM_1
#define TMC_UART_RX GPIO_NUM_21
#define TMC_UART_TX GPIO_NUM_22
#define TMC_UART_RX "gpio.21"
#define TMC_UART_TX "gpio.22"
#define X_TRINAMIC_DRIVER 2209
#define X_STEP_PIN GPIO_NUM_27
#define X_DIRECTION_PIN GPIO_NUM_26
#define X_STEP_PIN "gpio.27"
#define X_DIRECTION_PIN "gpio.26"
#define X_RSENSE TMC2209_RSENSE_DEFAULT
#define X_DRIVER_ADDRESS 1
#define DEFAULT_X_MICROSTEPS 16
#define Y_TRINAMIC_DRIVER 2209
#define Y_STEP_PIN GPIO_NUM_33
#define Y_DIRECTION_PIN GPIO_NUM_32
#define Y_STEP_PIN "gpio.33"
#define Y_DIRECTION_PIN "gpio.32"
#define Y_RSENSE TMC2209_RSENSE_DEFAULT
#define Y_DRIVER_ADDRESS 3
#define DEFAULT_Y_MICROSTEPS 16
#define Z_TRINAMIC_DRIVER 2209
#define Z_STEP_PIN GPIO_NUM_14
#define Z_DIRECTION_PIN GPIO_NUM_12
#define Z_STEP_PIN "gpio.14"
#define Z_DIRECTION_PIN "gpio.12"
#define Z_RSENSE TMC2209_RSENSE_DEFAULT
#define Z_DRIVER_ADDRESS 0
#define DEFAULT_Z_MICROSTEPS 16
#define A_TRINAMIC_DRIVER 2209
#define A_STEP_PIN GPIO_NUM_16
#define A_DIRECTION_PIN GPIO_NUM_17
#define A_STEP_PIN "gpio.16"
#define A_DIRECTION_PIN "gpio.17"
#define A_RSENSE TMC2209_RSENSE_DEFAULT
#define A_DRIVER_ADDRESS 2
#define DEFAULT_A_MICROSTEPS 16
#define X_LIMIT_PIN GPIO_NUM_34
#define Y_LIMIT_PIN GPIO_NUM_35
#define Z_LIMIT_PIN GPIO_NUM_15
#define A_LIMIT_PIN GPIO_NUM_36 // Labeled TB
#define PROBE_PIN GPIO_NUM_39 // Labeled TE
#define X_LIMIT_PIN "gpio.34"
#define Y_LIMIT_PIN "gpio.35"
#define Z_LIMIT_PIN "gpio.15"
#define A_LIMIT_PIN "gpio.36" // Labeled TB
#define PROBE_PIN "gpio.39" // Labeled TE
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_25
#define STEPPERS_DISABLE_PIN "gpio.25"
#define SPINDLE_TYPE SpindleType::RELAY
#define SPINDLE_OUTPUT_PIN GPIO_NUM_13 // labeled Fan
#define COOLANT_MIST_PIN GPIO_NUM_2 // Labeled Hotbed
#define COOLANT_FLOOD_PIN GPIO_NUM_4 // Labeled Heater
#define SPINDLE_OUTPUT_PIN "gpio.13" // labeled Fan
#define COOLANT_MIST_PIN "gpio.2" // Labeled Hotbed
#define COOLANT_FLOOD_PIN "gpio.4" // Labeled Heater

View File

@@ -52,28 +52,29 @@ void init_motors() {
if (n_axis >= 1) {
#ifdef X_TRINAMIC_DRIVER
myMotor[X_AXIS][0] = new Motors::TrinamicDriver(X_AXIS,
StepPins[X_AXIS][0]->get(),
DirectionPins[X_AXIS][0]->get(),
DisablePins[X_AXIS][0]->get(),
ClearToSendPins[X_AXIS][0]->get(),
X_TRINAMIC_DRIVER,
X_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[X_AXIS][0] =
new Motors::TrinamicDriver(X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_CS_PIN, X_TRINAMIC_DRIVER, X_RSENSE);
myMotor[X_AXIS][0] = new Motors::TrinamicDriver(X_AXIS,
StepPins[X_AXIS][0]->get(),
DirectionPins[X_AXIS][0]->get(),
DisablePins[X_AXIS][0]->get(),
ClearToSendPins[X_AXIS][0]->get(),
X_TRINAMIC_DRIVER,
X_RSENSE);
}
# elif (X_TRINAMIC_DRIVER == 2208 || X_TRINAMIC_DRIVER == 2209)
{
myMotor[X_AXIS][0] = new Motors::TrinamicUartDriver(
X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN, X_TRINAMIC_DRIVER, X_RSENSE, X_DRIVER_ADDRESS);
myMotor[X_AXIS][0] = new Motors::TrinamicUartDriver(X_AXIS,
StepPins[X_AXIS][0]->get(),
DirectionPins[X_AXIS][0]->get(),
DisablePins[X_AXIS][0]->get(),
X_TRINAMIC_DRIVER,
X_RSENSE,
X_DRIVER_ADDRESS);
}
# else
# error X Axis undefined motor p/n
# endif
#elif defined(X_SERVO_PIN)
myMotor[X_AXIS][0] = new Motors::RcServo(X_AXIS, X_SERVO_PIN);
#elif defined(X_UNIPOLAR)
myMotor[X_AXIS][0] = new Motors::UnipolarMotor(X_AXIS,
PhasePins[0][X_AXIS][0]->get(),
@@ -94,22 +95,25 @@ void init_motors() {
#endif
#ifdef X2_TRINAMIC_DRIVER
myMotor[X_AXIS][1] = new Motors::TrinamicDriver(X2_AXIS,
StepPins[X_AXIS][1]->get(),
DirectionPins[X_AXIS][1]->get(),
DisablePins[X_AXIS][1]->get(),
ClearToSendPins[X_AXIS][1]->get(),
X2_TRINAMIC_DRIVER,
X2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[X_AXIS][1] =
new Motors::TrinamicDriver(X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_CS_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE);
myMotor[X_AXIS][1] = new Motors::TrinamicDriver(X2_AXIS,
StepPins[X_AXIS][1]->get(),
DirectionPins[X_AXIS][1]->get(),
DisablePins[X_AXIS][1]->get(),
ClearToSendPins[X_AXIS][1]->get(),
X2_TRINAMIC_DRIVER,
X2_RSENSE);
}
# elif (X2_TRINAMIC_DRIVER == 2208 || X2_TRINAMIC_DRIVER == 2209)
{
myMotor[X_AXIS][1] = new Motors::TrinamicUartDriver(
X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN, X2_TRINAMIC_DRIVER, X2_RSENSE, X2_DRIVER_ADDRESS);
myMotor[X_AXIS][1] = new Motors::TrinamicUartDriver(X2_AXIS,
StepPins[X_AXIS][1]->get(),
DirectionPins[X_AXIS][1]->get(),
DisablePins[X_AXIS][1]->get(),
X2_TRINAMIC_DRIVER,
X2_RSENSE,
X2_DRIVER_ADDRESS);
}
# else
# error X2 Axis undefined motor p/n
@@ -135,28 +139,29 @@ void init_motors() {
if (n_axis >= 2) {
// this WILL be done better with settings
#ifdef Y_TRINAMIC_DRIVER
myMotor[Y_AXIS][0] = new Motors::TrinamicDriver(Y_AXIS,
StepPins[Y_AXIS][0]->get(),
DirectionPins[Y_AXIS][0]->get(),
DisablePins[Y_AXIS][0]->get(),
ClearToSendPins[Y_AXIS][0]->get(),
Y_TRINAMIC_DRIVER,
Y_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Y_AXIS][0] =
new Motors::TrinamicDriver(Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE);
myMotor[Y_AXIS][0] = new Motors::TrinamicDriver(Y_AXIS,
StepPins[Y_AXIS][0]->get(),
DirectionPins[Y_AXIS][0]->get(),
DisablePins[Y_AXIS][0]->get(),
ClearToSendPins[Y_AXIS][0]->get(),
Y_TRINAMIC_DRIVER,
Y_RSENSE);
}
# elif (Y_TRINAMIC_DRIVER == 2208 || Y_TRINAMIC_DRIVER == 2209)
{
myMotor[Y_AXIS][0] = new Motors::TrinamicUartDriver(
Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE, Y_DRIVER_ADDRESS);
myMotor[Y_AXIS][0] = new Motors::TrinamicUartDriver(Y_AXIS,
StepPins[Y_AXIS][0]->get(),
DirectionPins[Y_AXIS][0]->get(),
DisablePins[Y_AXIS][0]->get(),
Y_TRINAMIC_DRIVER,
Y_RSENSE,
Y_DRIVER_ADDRESS);
}
# else
# error Y Axis undefined motor p/n
# endif
#elif defined(Y_SERVO_PIN)
myMotor[Y_AXIS][0] = new Motors::RcServo(Y_AXIS, Y_SERVO_PIN);
#elif defined(Y_UNIPOLAR)
myMotor[Y_AXIS][0] = new Motors::UnipolarMotor(Y_AXIS,
PhasePins[0][Y_AXIS][0]->get(),
@@ -177,22 +182,25 @@ void init_motors() {
#endif
#ifdef Y2_TRINAMIC_DRIVER
myMotor[Y_AXIS][1] = new Motors::TrinamicDriver(Y2_AXIS,
StepPins[Y_AXIS][1]->get(),
DirectionPins[Y_AXIS][1]->get(),
DisablePins[Y_AXIS][1]->get(),
ClearToSendPins[Y_AXIS][1]->get(),
Y2_TRINAMIC_DRIVER,
Y2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Y_AXIS][1] =
new Motors::TrinamicDriver(Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_CS_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE);
myMotor[Y_AXIS][1] = new Motors::TrinamicDriver(Y2_AXIS,
StepPins[Y_AXIS][1]->get(),
DirectionPins[Y_AXIS][1]->get(),
DisablePins[Y_AXIS][1]->get(),
ClearToSendPins[Y_AXIS][1]->get(),
Y2_TRINAMIC_DRIVER,
Y2_RSENSE);
}
# elif (Y2_TRINAMIC_DRIVER == 2208 || Y2_TRINAMIC_DRIVER == 2209)
{
myMotor[Y_AXIS][1] = new Motors::TrinamicUartDriver(
Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN, Y2_TRINAMIC_DRIVER, Y2_RSENSE, Y2_DRIVER_ADDRESS);
myMotor[Y_AXIS][1] = new Motors::TrinamicUartDriver(Y2_AXIS,
StepPins[Y_AXIS][1]->get(),
DirectionPins[Y_AXIS][1]->get(),
DisablePins[Y_AXIS][1]->get(),
Y2_TRINAMIC_DRIVER,
Y2_RSENSE,
Y2_DRIVER_ADDRESS);
}
# else
# error Y2 Axis undefined motor p/n
@@ -218,28 +226,29 @@ void init_motors() {
if (n_axis >= 3) {
// this WILL be done better with settings
#ifdef Z_TRINAMIC_DRIVER
myMotor[Z_AXIS][0] = new Motors::TrinamicDriver(Z_AXIS,
StepPins[Z_AXIS][0]->get(),
DirectionPins[Z_AXIS][0]->get(),
DisablePins[Z_AXIS][0]->get(),
ClearToSendPins[Z_AXIS][0]->get(),
Z_TRINAMIC_DRIVER,
Z_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Z_AXIS][0] =
new Motors::TrinamicDriver(Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE);
myMotor[Z_AXIS][0] = new Motors::TrinamicDriver(Z_AXIS,
StepPins[Z_AXIS][0]->get(),
DirectionPins[Z_AXIS][0]->get(),
DisablePins[Z_AXIS][0]->get(),
ClearToSendPins[Z_AXIS][0]->get(),
Z_TRINAMIC_DRIVER,
Z_RSENSE);
}
# elif (Z_TRINAMIC_DRIVER == 2208 || Z_TRINAMIC_DRIVER == 2209)
{
myMotor[Z_AXIS][0] = new Motors::TrinamicUartDriver(
Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE, Z_DRIVER_ADDRESS);
myMotor[Z_AXIS][0] = new Motors::TrinamicUartDriver(Z_AXIS,
StepPins[Z_AXIS][0]->get(),
DirectionPins[Z_AXIS][0]->get(),
DisablePins[Z_AXIS][0]->get(),
Z_TRINAMIC_DRIVER,
Z_RSENSE,
Z_DRIVER_ADDRESS);
}
# else
# error Z Axis undefined motor p/n
# endif
#elif defined(Z_SERVO_PIN)
myMotor[Z_AXIS][0] = new Motors::RcServo(Z_AXIS, Z_SERVO_PIN);
#elif defined(Z_UNIPOLAR)
myMotor[Z_AXIS][0] = new Motors::UnipolarMotor(Z_AXIS,
PhasePins[0][Z_AXIS][0]->get(),
@@ -260,22 +269,25 @@ void init_motors() {
#endif
#ifdef Z2_TRINAMIC_DRIVER
myMotor[Z_AXIS][1] = new Motors::TrinamicDriver(Z2_AXIS,
StepPins[Z_AXIS][1]->get(),
DirectionPins[Z_AXIS][1]->get(),
DisablePins[Z_AXIS][1]->get(),
ClearToSendPins[Z_AXIS][1]->get(),
Z2_TRINAMIC_DRIVER,
Z2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[Z_AXIS][1] =
new Motors::TrinamicDriver(Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_CS_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE);
myMotor[Z_AXIS][1] = new Motors::TrinamicDriver(Z2_AXIS,
StepPins[Z_AXIS][1]->get(),
DirectionPins[Z_AXIS][1]->get(),
DisablePins[Z_AXIS][1]->get(),
ClearToSendPins[Z_AXIS][1]->get(),
Z2_TRINAMIC_DRIVER,
Z2_RSENSE);
}
# elif (Z2_TRINAMIC_DRIVER == 2208 || Z2_TRINAMIC_DRIVER == 2209)
{
myMotor[Z_AXIS][1] = new Motors::TrinamicUartDriver(
Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN, Z2_TRINAMIC_DRIVER, Z2_RSENSE, Z2_DRIVER_ADDRESS);
myMotor[Z_AXIS][1] = new Motors::TrinamicUartDriver(Z2_AXIS,
StepPins[Z_AXIS][1]->get(),
DirectionPins[Z_AXIS][1]->get(),
DisablePins[Z_AXIS][1]->get(),
Z2_TRINAMIC_DRIVER,
Z2_RSENSE,
Z2_DRIVER_ADDRESS);
}
# else
# error Z2 Axis undefined motor p/n
@@ -301,28 +313,29 @@ void init_motors() {
if (n_axis >= 4) {
// this WILL be done better with settings
#ifdef A_TRINAMIC_DRIVER
myMotor[A_AXIS][0] = new Motors::TrinamicDriver(A_AXIS,
StepPins[A_AXIS][0]->get(),
DirectionPins[A_AXIS][0]->get(),
DisablePins[A_AXIS][0]->get(),
ClearToSendPins[A_AXIS][0]->get(),
A_TRINAMIC_DRIVER,
A_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[A_AXIS][1] =
new Motors::TrinamicDriver(A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE);
myMotor[A_AXIS][0] = new Motors::TrinamicDriver(A_AXIS,
StepPins[A_AXIS][0]->get(),
DirectionPins[A_AXIS][0]->get(),
DisablePins[A_AXIS][0]->get(),
ClearToSendPins[A_AXIS][0]->get(),
A_TRINAMIC_DRIVER,
A_RSENSE);
}
# elif (A_TRINAMIC_DRIVER == 2208 || A_TRINAMIC_DRIVER == 2209)
{
myMotor[A_AXIS][0] = new Motors::TrinamicUartDriver(
A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_TRINAMIC_DRIVER, A_RSENSE, A_DRIVER_ADDRESS);
myMotor[A_AXIS][0] = new Motors::TrinamicUartDriver(A_AXIS,
StepPins[A_AXIS][0]->get(),
DirectionPins[A_AXIS][0]->get(),
DisablePins[A_AXIS][0]->get(),
A_TRINAMIC_DRIVER,
A_RSENSE,
A_DRIVER_ADDRESS);
}
# else
# error A Axis undefined motor p/n
# endif
#elif defined(A_SERVO_PIN)
myMotor[A_AXIS][0] = new Motors::RcServo(A_AXIS, A_SERVO_PIN);
#elif defined(A_UNIPOLAR)
myMotor[A_AXIS][0] = new Motors::UnipolarMotor(A_AXIS,
PhasePins[0][A_AXIS][0]->get(),
@@ -343,22 +356,25 @@ void init_motors() {
#endif
#ifdef A2_TRINAMIC_DRIVER
myMotor[A_AXIS][1] = new Motors::TrinamicDriver(A2_AXIS,
StepPins[A_AXIS][1]->get(),
DirectionPins[A_AXIS][1]->get(),
DisablePins[A_AXIS][1]->get(),
ClearToSendPins[A_AXIS][1]->get(),
A2_TRINAMIC_DRIVER,
A2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[A_AXIS][1] =
new Motors::TrinamicDriver(A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_CS_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE);
myMotor[A_AXIS][1] = new Motors::TrinamicDriver(A2_AXIS,
StepPins[A_AXIS][1]->get(),
DirectionPins[A_AXIS][1]->get(),
DisablePins[A_AXIS][1]->get(),
ClearToSendPins[A_AXIS][1]->get(),
A2_TRINAMIC_DRIVER,
A2_RSENSE);
}
# elif (A2_TRINAMIC_DRIVER == 2208 || A2_TRINAMIC_DRIVER == 2209)
{
myMotor[A_AXIS][1] = new Motors::TrinamicUartDriver(
A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN, A2_TRINAMIC_DRIVER, A2_RSENSE, A2_DRIVER_ADDRESS);
myMotor[A_AXIS][1] = new Motors::TrinamicUartDriver(A2_AXIS,
StepPins[A_AXIS][1]->get(),
DirectionPins[A_AXIS][1]->get(),
DisablePins[A_AXIS][1]->get(),
A2_TRINAMIC_DRIVER,
A2_RSENSE,
A2_DRIVER_ADDRESS);
}
# else
# error A2 Axis undefined motor p/n
@@ -384,28 +400,29 @@ void init_motors() {
if (n_axis >= 5) {
// this WILL be done better with settings
#ifdef B_TRINAMIC_DRIVER
myMotor[B_AXIS][0] = new Motors::TrinamicDriver(B_AXIS,
StepPins[B_AXIS][0]->get(),
DirectionPins[B_AXIS][0]->get(),
DisablePins[B_AXIS][0]->get(),
ClearToSendPins[B_AXIS][0]->get(),
B_TRINAMIC_DRIVER,
B_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[B_AXIS][1] =
new Motors::TrinamicDriver(B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE);
myMotor[B_AXIS][0] = new Motors::TrinamicDriver(B_AXIS,
StepPins[B_AXIS][0]->get(),
DirectionPins[B_AXIS][0]->get(),
DisablePins[B_AXIS][0]->get(),
ClearToSendPins[B_AXIS][0]->get(),
B_TRINAMIC_DRIVER,
B_RSENSE);
}
# elif (B_TRINAMIC_DRIVER == 2208 || B_TRINAMIC_DRIVER == 2209)
{
myMotor[B_AXIS][0] = new Motors::TrinamicUartDriver(
B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_TRINAMIC_DRIVER, B_RSENSE, B_DRIVER_ADDRESS);
myMotor[B_AXIS][0] = new Motors::TrinamicUartDriver(B_AXIS,
StepPins[B_AXIS][0]->get(),
DirectionPins[B_AXIS][0]->get(),
DisablePins[B_AXIS][0]->get(),
B_TRINAMIC_DRIVER,
B_RSENSE,
B_DRIVER_ADDRESS);
}
# else
# error B Axis undefined motor p/n
# endif
#elif defined(B_SERVO_PIN)
myMotor[B_AXIS][0] = new Motors::RcServo(B_AXIS, B_SERVO_PIN);
#elif defined(B_UNIPOLAR)
myMotor[B_AXIS][0] = new Motors::UnipolarMotor(B_AXIS,
PhasePins[0][B_AXIS][0]->get(),
@@ -426,22 +443,25 @@ void init_motors() {
#endif
#ifdef B2_TRINAMIC_DRIVER
myMotor[B_AXIS][1] = new Motors::TrinamicDriver(B2_AXIS,
StepPins[B_AXIS][1]->get(),
DirectionPins[B_AXIS][1]->get(),
DisablePins[B_AXIS][1]->get(),
ClearToSendPins[B_AXIS][1]->get(),
B2_TRINAMIC_DRIVER,
B2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[B_AXIS][1] =
new Motors::TrinamicDriver(B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_CS_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE);
myMotor[B_AXIS][1] = new Motors::TrinamicDriver(B2_AXIS,
StepPins[B_AXIS][1]->get(),
DirectionPins[B_AXIS][1]->get(),
DisablePins[B_AXIS][1]->get(),
ClearToSendPins[B_AXIS][1]->get(),
B2_TRINAMIC_DRIVER,
B2_RSENSE);
}
# elif (B2_TRINAMIC_DRIVER == 2208 || B2_TRINAMIC_DRIVER == 2209)
{
myMotor[B_AXIS][1] = new Motors::TrinamicUartDriver(
B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN, B2_TRINAMIC_DRIVER, B2_RSENSE, B2_DRIVER_ADDRESS);
myMotor[B_AXIS][1] = new Motors::TrinamicUartDriver(B2_AXIS,
StepPins[B_AXIS][1]->get(),
DirectionPins[B_AXIS][1]->get(),
DisablePins[B_AXIS][1]->get(),
B2_TRINAMIC_DRIVER,
B2_RSENSE,
B2_DRIVER_ADDRESS);
}
# else
# error B2 Axis undefined motor p/n
@@ -467,28 +487,29 @@ void init_motors() {
if (n_axis >= 6) {
// this WILL be done better with settings
#ifdef C_TRINAMIC_DRIVER
myMotor[C_AXIS][0] = new Motors::TrinamicDriver(C_AXIS,
StepPins[C_AXIS][0]->get(),
DirectionPins[C_AXIS][0]->get(),
DisablePins[C_AXIS][0]->get(),
ClearToSendPins[C_AXIS][0]->get(),
C_TRINAMIC_DRIVER,
C_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[C_AXIS][1] =
new Motors::TrinamicDriver(C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE);
myMotor[C_AXIS][0] = new Motors::TrinamicDriver(C_AXIS,
StepPins[C_AXIS][0]->get(),
DirectionPins[C_AXIS][0]->get(),
DisablePins[C_AXIS][0]->get(),
ClearToSendPins[C_AXIS][0]->get(),
C_TRINAMIC_DRIVER,
C_RSENSE);
}
# elif (C_TRINAMIC_DRIVER == 2208 || C_TRINAMIC_DRIVER == 2209)
{
myMotor[C_AXIS][0] = new Motors::TrinamicUartDriver(
C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_TRINAMIC_DRIVER, C_RSENSE, C_DRIVER_ADDRESS);
myMotor[C_AXIS][0] = new Motors::TrinamicUartDriver(C_AXIS,
StepPins[C_AXIS][0]->get(),
DirectionPins[C_AXIS][0]->get(),
DisablePins[C_AXIS][0]->get(),
C_TRINAMIC_DRIVER,
C_RSENSE,
C_DRIVER_ADDRESS);
}
# else
# error C Axis undefined motor p/n
# endif
#elif defined(C_SERVO_PIN)
myMotor[C_AXIS][0] = new Motors::RcServo(C_AXIS, C_SERVO_PIN);
#elif defined(C_UNIPOLAR)
myMotor[C_AXIS][0] = new Motors::UnipolarMotor(C_AXIS,
PhasePins[0][C_AXIS][0]->get(),
@@ -509,22 +530,25 @@ void init_motors() {
#endif
#ifdef C2_TRINAMIC_DRIVER
myMotor[C_AXIS][1] = new Motors::TrinamicDriver(C2_AXIS,
StepPins[C_AXIS][1]->get(),
DirectionPins[C_AXIS][1]->get(),
DisablePins[C_AXIS][1]->get(),
ClearToSendPins[C_AXIS][1]->get(),
C2_TRINAMIC_DRIVER,
C2_RSENSE);
# if (X_TRINAMIC_DRIVER == 2130 || X_TRINAMIC_DRIVER == 5160)
{
myMotor[C_AXIS][1] =
new Motors::TrinamicDriver(C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_CS_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE);
myMotor[C_AXIS][1] = new Motors::TrinamicDriver(C2_AXIS,
StepPins[C_AXIS][1]->get(),
DirectionPins[C_AXIS][1]->get(),
DisablePins[C_AXIS][1]->get(),
ClearToSendPins[C_AXIS][1]->get(),
C2_TRINAMIC_DRIVER,
C2_RSENSE);
}
# elif (C2_TRINAMIC_DRIVER == 2208 || C2_TRINAMIC_DRIVER == 2209)
{
myMotor[C_AXIS][1] = new Motors::TrinamicUartDriver(
C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN, C2_TRINAMIC_DRIVER, C2_RSENSE, C2_DRIVER_ADDRESS);
myMotor[C_AXIS][1] = new Motors::TrinamicUartDriver(C2_AXIS,
StepPins[C_AXIS][1]->get(),
DirectionPins[C_AXIS][1]->get(),
DisablePins[C_AXIS][1]->get(),
C2_TRINAMIC_DRIVER,
C2_RSENSE,
C2_DRIVER_ADDRESS);
}
# else
# error C2 Axis undefined motor p/n
@@ -665,4 +689,4 @@ void motors_unstep() {
myMotor[axis][0]->unstep();
myMotor[axis][1]->unstep();
}
}
}

View File

@@ -29,7 +29,7 @@ namespace Motors {
/* HW Serial Constructor. */
TrinamicUartDriver::TrinamicUartDriver(
uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin, uint16_t driver_part_number, float r_sense, uint8_t addr) :
uint8_t axis_index, Pin step_pin, Pin dir_pin, Pin disable_pin, uint16_t driver_part_number, float r_sense, uint8_t addr) :
StandardStepper(axis_index, step_pin, dir_pin, disable_pin) {
_driver_part_number = driver_part_number;
_has_errors = false;
@@ -81,15 +81,15 @@ namespace Motors {
void TrinamicUartDriver::config_message() { //TODO: The RX/TX pin could be added to the msg.
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
"%s motor Trinamic TMC%d Step:%s Dir:%s Disable:%s UART%d Rx:%s Tx:%s Addr:%d R:%0.3f %s",
"%s motor Trinamic TMC%d Step:%s Dir:%s Disable:%s UART%d Rx:%d Tx:%d Addr:%d R:%0.3f %s",
reportAxisNameMsg(_axis_index, _dual_axis_index),
_driver_part_number,
pinName(_step_pin).c_str(),
pinName(_dir_pin).c_str(),
pinName(_disable_pin).c_str(),
_step_pin.name().c_str(),
_dir_pin.name().c_str(),
_disable_pin.name().c_str(),
TMC_UART,
pinName(TMC_UART_RX),
pinName(TMC_UART_TX),
int(TMC_UART_RX),
int(TMC_UART_TX),
this->addr,
_r_sense,
reportAxisLimitsMsg(_axis_index));
@@ -295,7 +295,7 @@ namespace Motors {
_disabled = disable;
digitalWrite(_disable_pin, _disabled);
_disable_pin.write(_disabled);
#ifdef USE_TRINAMIC_ENABLE
if (_disabled) {
@@ -367,4 +367,4 @@ namespace Motors {
return false; // no error
}
}
}

View File

@@ -55,12 +55,14 @@ const double TRINAMIC_UART_FCLK = 12700000.0; // Internal clock Approx (Hz) use
# define TMC_UART UART_NUM_2
#endif
// HACK! 254 = undefined. We can't use UNDEFINED_PIN, we should be using Pin class!
#ifndef TMC_UART_RX
# define TMC_UART_RX UNDEFINED_PIN
# define TMC_UART_RX 254
#endif
#ifndef TMC_UART_TX
# define TMC_UART_TX UNDEFINED_PIN
# define TMC_UART_TX 254
#endif
extern HardwareSerial tmc_serial;
@@ -76,13 +78,8 @@ namespace Motors {
class TrinamicUartDriver : public StandardStepper {
public:
TrinamicUartDriver(uint8_t axis_index,
uint8_t step_pin,
uint8_t dir_pin,
uint8_t disable_pin,
uint16_t driver_part_number,
float r_senseS,
uint8_t address);
TrinamicUartDriver(
uint8_t axis_index, Pin step_pin, Pin dir_pin, Pin disable_pin, uint16_t driver_part_number, float r_senseS, uint8_t address);
void config_message();
void hw_serial_init();
@@ -128,4 +125,4 @@ namespace Motors {
// void config_message() override;
};
}
}

View File

@@ -85,6 +85,11 @@ public:
detail->setAttr(attributes);
}
inline void reset() const {
auto detail = Pins::PinLookup::_instance.GetPin(_index);
detail->reset();
}
inline void on() const { write(1); }
inline void off() const { write(0); }

View File

@@ -25,7 +25,7 @@ namespace Pins {
if (high != _isHigh) {
_isHigh = high;
if (shouldEvent()) {
WriteSerial( "Write %s < %d", toString().c_str(), high);
WriteSerial("Write %s < %d", toString().c_str(), high);
}
}
_implementation->write(high);
@@ -38,6 +38,14 @@ namespace Pins {
}
return result;
}
void DebugPinDetail::reset() {
_implementation->reset();
if (shouldEvent()) {
WriteSerial("Reset %s", toString().c_str());
}
}
void DebugPinDetail::setAttr(PinAttributes value) {
char buf[10];
int n = 0;

View File

@@ -34,6 +34,7 @@ namespace Pins {
void write(int high) override;
int read() override;
void setAttr(PinAttributes value) override;
void reset() override;
// ISR's:
void attachInterrupt(void (*callback)(void*), void* arg, int mode) override;

View File

@@ -11,6 +11,7 @@ namespace Pins {
int ErrorPinDetail::read() { Assert(false, "Cannot read from an error pin."); }
void ErrorPinDetail::setAttr(PinAttributes value) { /* Fine, this won't get you anywhere. */
}
void ErrorPinDetail::reset() {}
String ErrorPinDetail::toString() const { return "ERROR_PIN"; }
}

View File

@@ -15,6 +15,7 @@ namespace Pins {
void write(int high) override;
int read() override;
void setAttr(PinAttributes value) override;
void reset() override;
String toString() const override;

View File

@@ -164,6 +164,11 @@ namespace Pins {
__pinMode(_index, pinModeValue);
}
void GPIOPinDetail::reset() {
gpio_reset_pin(gpio_num_t(_index));
__pinMode(_index, INPUT);
}
void GPIOPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) {
Assert(_currentMode.has(PinAttributes::ISR),

View File

@@ -21,6 +21,7 @@ namespace Pins {
void write(int high) override;
int read() override;
void setAttr(PinAttributes value) override;
void reset() override;
// ISR's:
void attachInterrupt(void (*callback)(void*), void* arg, int mode) override;

View File

@@ -62,6 +62,8 @@ namespace Pins {
}
}
void I2SOPinDetail::reset() {}
String I2SOPinDetail::toString() const { return String("I2SO.") + int(_index); }
}

View File

@@ -19,6 +19,7 @@ namespace Pins {
void write(int high) override;
int read() override;
void setAttr(PinAttributes value) override;
void reset() override;
String toString() const override;

View File

@@ -23,12 +23,13 @@ namespace Pins {
PinDetail& operator=(PinDetail&& o) = delete;
virtual PinCapabilities capabilities() const = 0;
virtual PinAttributes attributes() const = 0;
virtual PinAttributes attributes() const = 0;
// I/O:
virtual void write(int high) = 0;
virtual int read() = 0;
virtual void setAttr(PinAttributes value) = 0;
virtual void reset() = 0;
// ISR's.
virtual void attachInterrupt(void (*callback)(void*), void* arg, int mode);

View File

@@ -13,6 +13,7 @@ namespace Pins {
void VoidPinDetail::write(int high) {}
int VoidPinDetail::read() { return 0; }
void VoidPinDetail::setAttr(PinAttributes value) {}
void VoidPinDetail::reset() {}
String VoidPinDetail::toString() const { return ""; }

View File

@@ -16,6 +16,7 @@ namespace Pins {
void write(int high) override;
int read() override;
void setAttr(PinAttributes value) override;
void reset() override;
String toString() const override;

View File

@@ -5,7 +5,7 @@
#include <nvs.h>
#include "WebUI/ESPResponse.h"
#include "Eeprom.h" // For CoordIndex
#include "GCode.h"
// Initialize the configuration subsystem
void settings_init();

View File

@@ -238,12 +238,6 @@ void make_settings() {
def = &axis_defaults[axis];
axis_settings[axis] = new AxisSettings(def->name);
}
x_axis_settings = axis_settings[X_AXIS];
y_axis_settings = axis_settings[Y_AXIS];
z_axis_settings = axis_settings[Z_AXIS];
a_axis_settings = axis_settings[A_AXIS];
b_axis_settings = axis_settings[B_AXIS];
c_axis_settings = axis_settings[C_AXIS];
for (axis = 0; axis < number_axis->get(); axis++) {
def = &axis_defaults[axis];
auto setting =

View File

@@ -158,27 +158,8 @@ namespace Spindles {
}
void _10v::deinit() {
#ifdef SPINDLE_OUTPUT_PIN
gpio_reset_pin(SPINDLE_OUTPUT_PIN);
pinMode(SPINDLE_OUTPUT_PIN, INPUT);
#endif
#ifdef SPINDLE_ENABLE_PIN
gpio_reset_pin(SPINDLE_ENABLE_PIN);
pinMode(SPINDLE_ENABLE_PIN, INPUT);
#endif
#ifdef SPINDLE_DIR_PIN
gpio_reset_pin(SPINDLE_DIR_PIN);
pinMode(SPINDLE_DIR_PIN, INPUT);
#endif
#ifdef SPINDLE_FORWARD_PIN
gpio_reset_pin(SPINDLE_FORWARD_PIN);
pinMode(SPINDLE_FORWARD_PIN, INPUT);
#endif
#ifdef SPINDLE_REVERSE_PIN
gpio_reset_pin(SPINDLE_FORWARD_PIN);
pinMode(SPINDLE_FORWARD_PIN, INPUT);
#endif
PWM::deinit();
_forward_pin.reset();
_reverse_pin.reset();
}
}

View File

@@ -48,25 +48,23 @@ namespace Spindles {
#ifdef LASER_OUTPUT_PIN
_output_pin = LASER_OUTPUT_PIN;
#else
_output_pin = UNDEFINED_PIN;
_output_pin = Pin::UNDEFINED;
#endif
_invert_pwm = spindle_output_invert->get();
#ifdef LASER_ENABLE_PIN
_enable_pin = LASER_ENABLE_PIN;
#else
_enable_pin = UNDEFINED_PIN;
_enable_pin = Pin::UNDEFINED;
#endif
if (_output_pin == UNDEFINED_PIN) {
if (_output_pin == Pin::UNDEFINED) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: LASER_OUTPUT_PIN not defined");
return; // We cannot continue without the output pin
}
_off_with_zero_speed = spindle_enbl_off_with_zero_speed->get();
_direction_pin = UNDEFINED_PIN;
_direction_pin = Pin::UNDEFINED;
is_reversable = false;
_pwm_freq = spindle_pwm_freq->get();
@@ -88,14 +86,8 @@ namespace Spindles {
void Laser::deinit() {
stop();
#ifdef LASER_OUTPUT_PIN
gpio_reset_pin(LASER_OUTPUT_PIN);
pinMode(LASER_OUTPUT_PIN, INPUT);
#endif
#ifdef LASER_ENABLE_PIN
gpio_reset_pin(LASER_ENABLE_PIN);
pinMode(LASER_ENABLE_PIN, INPUT);
#endif
_output_pin.reset();
_enable_pin.reset();
}
}

View File

@@ -201,9 +201,10 @@ namespace Spindles {
_current_pwm_duty = duty;
if (_invert_pwm) {
duty = (1 << _pwm_precision) - duty;
}
// TODO FIXME:
// if (_invert_pwm) {
// duty = (1 << _pwm_precision) - duty;
// }
ledcWrite(_pwm_chan_num, duty);
}
@@ -249,18 +250,8 @@ namespace Spindles {
void PWM::deinit() {
stop();
#ifdef SPINDLE_OUTPUT_PIN
gpio_reset_pin(SPINDLE_OUTPUT_PIN);
pinMode(SPINDLE_OUTPUT_PIN, INPUT);
#endif
#ifdef SPINDLE_ENABLE_PIN
gpio_reset_pin(SPINDLE_ENABLE_PIN);
pinMode(SPINDLE_ENABLE_PIN, INPUT);
#endif
#ifdef SPINDLE_DIR_PIN
gpio_reset_pin(SPINDLE_DIR_PIN);
pinMode(SPINDLE_DIR_PIN, INPUT);
#endif
_output_pin.reset();
_enable_pin.reset();
_direction_pin.reset();
}
}