mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-09 13:50:51 +02:00
Made everything compile again. This should be a first working version.
This commit is contained in:
@@ -1,7 +1,5 @@
|
||||
#pragma once
|
||||
|
||||
extern void grbl_msg_sendf(uint8_t client, MsgLevel level, const char* format, ...);
|
||||
|
||||
#undef Assert
|
||||
|
||||
#define Stringify(x) #x
|
||||
@@ -10,7 +8,6 @@ extern void grbl_msg_sendf(uint8_t client, MsgLevel level, const char* format, .
|
||||
{ \
|
||||
if (!(condition)) { \
|
||||
const char* ch = #condition " (@line " Stringify2(__LINE__) ")"; \
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Error, ch); \
|
||||
throw ch; \
|
||||
} \
|
||||
}
|
||||
|
@@ -59,6 +59,12 @@ Some features should not be changed. See notes below.
|
||||
|
||||
#define USE_RMT_STEPS
|
||||
|
||||
// Define some 'pin' things that will error if used in the program. The *only* thing that should
|
||||
// use pins is the PinSettingsDefinitions.cpp file
|
||||
#ifndef UNDEFINED_PIN
|
||||
# define UNDEFINED_PIN static_assert(false, "Don't use me!");
|
||||
#endif
|
||||
|
||||
// Include the file that loads the machine-specific config file.
|
||||
// machine.h must be edited to choose the desired file.
|
||||
#include "Machine.h"
|
||||
@@ -539,7 +545,7 @@ const int DEBOUNCE_PERIOD = 32; // in milliseconds default 32 microseconds
|
||||
// these commands may be undesirable. Simply comment the desired macro to disable it.
|
||||
#define ENABLE_RESTORE_WIPE_ALL // '$RST=*' Default enabled. Comment to disable.
|
||||
#define ENABLE_RESTORE_DEFAULT_SETTINGS // '$RST=$' Default enabled. Comment to disable.
|
||||
#define ENABLE_RESTORE_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
|
||||
#define ENABLE_RESTORE_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
|
||||
|
||||
// Additional settings have been added to the original set that you see with the $$ command
|
||||
// Some senders may not be able to parse anything different from the original set
|
||||
|
@@ -41,18 +41,18 @@
|
||||
// It should be included at the outset to know the machine configuration.
|
||||
#include "Config.h"
|
||||
|
||||
# include <stdint.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/* Assert */
|
||||
# if defined(I2S_OUT_NUM_BITS)
|
||||
# if (I2S_OUT_NUM_BITS != 16) && (I2S_OUT_NUM_BITS != 32)
|
||||
# error "I2S_OUT_NUM_BITS should be 16 or 32"
|
||||
# endif
|
||||
# else
|
||||
# define I2S_OUT_NUM_BITS 32
|
||||
#if defined(I2S_OUT_NUM_BITS)
|
||||
# if (I2S_OUT_NUM_BITS != 16) && (I2S_OUT_NUM_BITS != 32)
|
||||
# error "I2S_OUT_NUM_BITS should be 16 or 32"
|
||||
# endif
|
||||
#else
|
||||
# define I2S_OUT_NUM_BITS 32
|
||||
#endif
|
||||
|
||||
# define I2SO(n) (I2S_OUT_PIN_BASE + n)
|
||||
// # define I2SO(n) (I2S_OUT_PIN_BASE + n)
|
||||
|
||||
/* 16-bit mode: 1000000 usec / ((160000000 Hz) / 10 / 2) x 16 bit/pulse x 2(stereo) = 4 usec/pulse */
|
||||
/* 32-bit mode: 1000000 usec / ((160000000 Hz) / 5 / 2) x 32 bit/pulse x 2(stereo) = 4 usec/pulse */
|
||||
|
@@ -317,7 +317,7 @@ void limits_init() {
|
||||
for (int axis = 0; axis < n_axis; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
Pin pin;
|
||||
if ((pin = limit_pins[axis][gang_index]->get()) != Pin::UNDEFINED) {
|
||||
if ((pin = LimitPins[axis][gang_index]->get()) != Pin::UNDEFINED) {
|
||||
pin.setAttr(mode);
|
||||
limit_mask |= bit(axis);
|
||||
if (hard_limits->get()) {
|
||||
@@ -351,7 +351,7 @@ void limits_disable() {
|
||||
auto n_axis = number_axis->get();
|
||||
for (int axis = 0; axis < n_axis; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
Pin pin = limit_pins[axis][gang_index]->get();
|
||||
Pin pin = LimitPins[axis][gang_index]->get();
|
||||
if (pin != Pin::UNDEFINED) {
|
||||
pin.detachInterrupt();
|
||||
}
|
||||
@@ -367,7 +367,7 @@ AxisMask limits_get_state() {
|
||||
auto n_axis = number_axis->get();
|
||||
for (int axis = 0; axis < n_axis; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
Pin pin = limit_pins[axis][gang_index]->get();
|
||||
Pin pin = LimitPins[axis][gang_index]->get();
|
||||
if (pin != Pin::UNDEFINED) {
|
||||
if (limit_invert->get()) {
|
||||
pinMask |= (!pin.read() << axis);
|
||||
|
@@ -20,6 +20,5 @@ const uint32_t fTimers = 80000000; // a reference to the speed of ESP32 timers
|
||||
// =============== Don't change or comment these out ======================
|
||||
// They are for legacy purposes and will not affect your I/O
|
||||
|
||||
const int STEP_MASK = B111111;
|
||||
|
||||
const int STEP_MASK = 0x3F; // 111111
|
||||
const int PROBE_MASK = 1;
|
||||
|
@@ -15,7 +15,7 @@
|
||||
TODO
|
||||
Make sure public/private/protected is cleaned up.
|
||||
Only a few Unipolar axes have been setup in init()
|
||||
Get rid of Z_SERVO, just reply on Z_SERVO_PIN
|
||||
Get rid of Z_SERVO, just reply on ServoPins[Z_AXIS][0]->get()
|
||||
Deal with custom machine ... machine_trinamic_setup();
|
||||
Class is ready to deal with non SPI pins, but they have not been needed yet.
|
||||
It would be nice in the config message though
|
||||
@@ -51,29 +51,52 @@ void init_motors() {
|
||||
|
||||
if (n_axis >= 1) {
|
||||
#ifdef X_TRINAMIC_DRIVER
|
||||
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);
|
||||
#elif defined(X_SERVO_PIN)
|
||||
myMotor[X_AXIS][0] = new Motors::RcServo(X_AXIS, X_SERVO_PIN);
|
||||
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 defined(X_UNIPOLAR)
|
||||
myMotor[X_AXIS][0] = new Motors::UnipolarMotor(X_AXIS, X_PIN_PHASE_0, X_PIN_PHASE_1, X_PIN_PHASE_2, X_PIN_PHASE_3);
|
||||
#elif defined(X_STEP_PIN)
|
||||
myMotor[X_AXIS][0] = new Motors::StandardStepper(X_AXIS, X_STEP_PIN, X_DIRECTION_PIN, X_DISABLE_PIN);
|
||||
myMotor[X_AXIS][0] = new Motors::UnipolarMotor(X_AXIS,
|
||||
PhasePins[0][X_AXIS][0]->get(),
|
||||
PhasePins[1][X_AXIS][0]->get(),
|
||||
PhasePins[2][X_AXIS][0]->get(),
|
||||
PhasePins[3][X_AXIS][0]->get());
|
||||
#elif defined(X_DYNAMIXEL_ID)
|
||||
myMotor[X_AXIS][0] = new Motors::Dynamixel2(X_AXIS, X_DYNAMIXEL_ID, DYNAMIXEL_TXD, DYNAMIXEL_RXD, DYNAMIXEL_RTS);
|
||||
myMotor[X_AXIS][0] =
|
||||
new Motors::Dynamixel2(X_AXIS, X_DYNAMIXEL_ID, DynamixelTXDPin->get(), DynamixelRXDPin->get(), DynamixelRTSPin->get());
|
||||
#else
|
||||
myMotor[X_AXIS][0] = new Motors::Nullmotor(X_AXIS);
|
||||
if (ServoPins[X_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[X_AXIS][0] = new Motors::RcServo(X_AXIS, ServoPins[X_AXIS][0]->get());
|
||||
else if (StepPins[X_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[X_AXIS][0] = new Motors::StandardStepper(
|
||||
X_AXIS, StepPins[X_AXIS][0]->get(), DirectionPins[X_AXIS][0]->get(), DisablePins[X_AXIS][0]->get());
|
||||
else
|
||||
myMotor[X_AXIS][0] = new Motors::Nullmotor(X_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef X2_TRINAMIC_DRIVER
|
||||
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 defined(X2_UNIPOLAR)
|
||||
myMotor[X_AXIS][1] = new Motors::UnipolarMotor(X2_AXIS, X2_PIN_PHASE_0, X2_PIN_PHASE_1, X2_PIN_PHASE_2, X2_PIN_PHASE_3);
|
||||
#elif defined(X2_STEP_PIN)
|
||||
myMotor[X_AXIS][1] = new Motors::StandardStepper(X2_AXIS, X2_STEP_PIN, X2_DIRECTION_PIN, X2_DISABLE_PIN);
|
||||
myMotor[X_AXIS][1] = new Motors::UnipolarMotor(X2_AXIS,
|
||||
PhasePins[1][X_AXIS][1]->get(),
|
||||
PhasePins[1][X_AXIS][1]->get(),
|
||||
PhasePins[2][X_AXIS][1]->get(),
|
||||
PhasePins[3][X_AXIS][1]->get());
|
||||
#else
|
||||
myMotor[X_AXIS][1] = new Motors::Nullmotor(X2_AXIS);
|
||||
if (StepPins[X_AXIS][1]->get() != Pin::UNDEFINED)
|
||||
myMotor[X_AXIS][1] = new Motors::StandardStepper(
|
||||
X2_AXIS, StepPins[X_AXIS][1]->get(), DirectionPins[X_AXIS][1]->get(), DisablePins[X_AXIS][1]->get());
|
||||
else
|
||||
myMotor[X_AXIS][1] = new Motors::Nullmotor(X2_AXIS);
|
||||
#endif
|
||||
} else {
|
||||
myMotor[X_AXIS][0] = new Motors::Nullmotor(X_AXIS);
|
||||
@@ -83,29 +106,52 @@ 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, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN, Y_CS_PIN, Y_TRINAMIC_DRIVER, Y_RSENSE);
|
||||
#elif defined(Y_SERVO_PIN)
|
||||
myMotor[Y_AXIS][0] = new Motors::RcServo(Y_AXIS, Y_SERVO_PIN);
|
||||
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 defined(Y_UNIPOLAR)
|
||||
myMotor[Y_AXIS][0] = new Motors::UnipolarMotor(Y_AXIS, Y_PIN_PHASE_0, Y_PIN_PHASE_1, Y_PIN_PHASE_2, Y_PIN_PHASE_3);
|
||||
#elif defined(Y_STEP_PIN)
|
||||
myMotor[Y_AXIS][0] = new Motors::StandardStepper(Y_AXIS, Y_STEP_PIN, Y_DIRECTION_PIN, Y_DISABLE_PIN);
|
||||
myMotor[Y_AXIS][0] = new Motors::UnipolarMotor(Y_AXIS,
|
||||
PhasePins[0][Y_AXIS][0]->get(),
|
||||
PhasePins[1][Y_AXIS][0]->get(),
|
||||
PhasePins[2][Y_AXIS][0]->get(),
|
||||
PhasePins[3][Y_AXIS][0]->get());
|
||||
#elif defined(Y_DYNAMIXEL_ID)
|
||||
myMotor[Y_AXIS][0] = new Motors::Dynamixel2(Y_AXIS, Y_DYNAMIXEL_ID, DYNAMIXEL_TXD, DYNAMIXEL_RXD, DYNAMIXEL_RTS);
|
||||
myMotor[Y_AXIS][0] =
|
||||
new Motors::Dynamixel2(Y_AXIS, Y_DYNAMIXEL_ID, DynamixelTXDPin->get(), DynamixelRXDPin->get(), DynamixelRTSPin->get());
|
||||
#else
|
||||
myMotor[Y_AXIS][0] = new Motors::Nullmotor(Y_AXIS);
|
||||
if (ServoPins[Y_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[Y_AXIS][0] = new Motors::RcServo(Y_AXIS, ServoPins[Y_AXIS][0]->get());
|
||||
else if (StepPins[Y_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[Y_AXIS][0] = new Motors::StandardStepper(
|
||||
Y_AXIS, StepPins[Y_AXIS][0]->get(), DirectionPins[Y_AXIS][0]->get(), DisablePins[Y_AXIS][0]->get());
|
||||
else
|
||||
myMotor[Y_AXIS][0] = new Motors::Nullmotor(Y_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef Y2_TRINAMIC_DRIVER
|
||||
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 defined(Y2_UNIPOLAR)
|
||||
myMotor[Y_AXIS][1] = new Motors::UnipolarMotor(Y2_AXIS, Y2_PIN_PHASE_0, Y2_PIN_PHASE_1, Y2_PIN_PHASE_2, Y2_PIN_PHASE_3);
|
||||
#elif defined(Y2_STEP_PIN)
|
||||
myMotor[Y_AXIS][1] = new Motors::StandardStepper(Y2_AXIS, Y2_STEP_PIN, Y2_DIRECTION_PIN, Y2_DISABLE_PIN);
|
||||
myMotor[Y_AXIS][1] = new Motors::UnipolarMotor(Y2_AXIS,
|
||||
PhasePins[1][Y_AXIS][1]->get(),
|
||||
PhasePins[1][Y_AXIS][1]->get(),
|
||||
PhasePins[2][Y_AXIS][1]->get(),
|
||||
PhasePins[3][Y_AXIS][1]->get());
|
||||
#else
|
||||
myMotor[Y_AXIS][1] = new Motors::Nullmotor(Y2_AXIS);
|
||||
if (StepPins[Y_AXIS][1]->get() != Pin::UNDEFINED)
|
||||
myMotor[Y_AXIS][1] = new Motors::StandardStepper(
|
||||
Y2_AXIS, StepPins[Y_AXIS][1]->get(), DirectionPins[Y_AXIS][1]->get(), DisablePins[Y_AXIS][1]->get());
|
||||
else
|
||||
myMotor[Y_AXIS][1] = new Motors::Nullmotor(Y2_AXIS);
|
||||
#endif
|
||||
} else {
|
||||
myMotor[Y_AXIS][0] = new Motors::Nullmotor(Y_AXIS);
|
||||
@@ -115,29 +161,52 @@ 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, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN, Z_CS_PIN, Z_TRINAMIC_DRIVER, Z_RSENSE);
|
||||
#elif defined(Z_SERVO_PIN)
|
||||
myMotor[Z_AXIS][0] = new Motors::RcServo(Z_AXIS, Z_SERVO_PIN);
|
||||
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 defined(Z_UNIPOLAR)
|
||||
myMotor[Z_AXIS][0] = new Motors::UnipolarMotor(Z_AXIS, Z_PIN_PHASE_0, Z_PIN_PHASE_1, Z_PIN_PHASE_2, Z_PIN_PHASE_3);
|
||||
#elif defined(Z_STEP_PIN)
|
||||
myMotor[Z_AXIS][0] = new Motors::StandardStepper(Z_AXIS, Z_STEP_PIN, Z_DIRECTION_PIN, Z_DISABLE_PIN);
|
||||
myMotor[Z_AXIS][0] = new Motors::UnipolarMotor(Z_AXIS,
|
||||
PhasePins[0][Z_AXIS][0]->get(),
|
||||
PhasePins[1][Z_AXIS][0]->get(),
|
||||
PhasePins[2][Z_AXIS][0]->get(),
|
||||
PhasePins[3][Z_AXIS][0]->get());
|
||||
#elif defined(Z_DYNAMIXEL_ID)
|
||||
myMotor[Z_AXIS][0] = new Motors::Dynamixel2(Z_AXIS, Z_DYNAMIXEL_ID, DYNAMIXEL_TXD, DYNAMIXEL_RXD, DYNAMIXEL_RTS);
|
||||
myMotor[Z_AXIS][0] =
|
||||
new Motors::Dynamixel2(Z_AXIS, Z_DYNAMIXEL_ID, DynamixelTXDPin->get(), DynamixelRXDPin->get(), DynamixelRTSPin->get());
|
||||
#else
|
||||
myMotor[Z_AXIS][0] = new Motors::Nullmotor(Z_AXIS);
|
||||
if (ServoPins[Z_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[Z_AXIS][0] = new Motors::RcServo(Z_AXIS, ServoPins[Z_AXIS][0]->get());
|
||||
else if (StepPins[Z_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[Z_AXIS][0] = new Motors::StandardStepper(
|
||||
Z_AXIS, StepPins[Z_AXIS][0]->get(), DirectionPins[Z_AXIS][0]->get(), DisablePins[Z_AXIS][0]->get());
|
||||
else
|
||||
myMotor[Z_AXIS][0] = new Motors::Nullmotor(Z_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef Z2_TRINAMIC_DRIVER
|
||||
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 defined(Z2_UNIPOLAR)
|
||||
myMotor[Z_AXIS][1] = new Motors::UnipolarMotor(Z2_AXIS, Z2_PIN_PHASE_0, Z2_PIN_PHASE_1, Z2_PIN_PHASE_2, Z2_PIN_PHASE_3);
|
||||
#elif defined(Z2_STEP_PIN)
|
||||
myMotor[Z_AXIS][1] = new Motors::StandardStepper(Z2_AXIS, Z2_STEP_PIN, Z2_DIRECTION_PIN, Z2_DISABLE_PIN);
|
||||
myMotor[Z_AXIS][1] = new Motors::UnipolarMotor(Z2_AXIS,
|
||||
PhasePins[1][Z_AXIS][1]->get(),
|
||||
PhasePins[1][Z_AXIS][1]->get(),
|
||||
PhasePins[2][Z_AXIS][1]->get(),
|
||||
PhasePins[3][Z_AXIS][1]->get());
|
||||
#else
|
||||
myMotor[Z_AXIS][1] = new Motors::Nullmotor(Z2_AXIS);
|
||||
if (StepPins[Z_AXIS][1]->get() != Pin::UNDEFINED)
|
||||
myMotor[Z_AXIS][1] = new Motors::StandardStepper(
|
||||
Z2_AXIS, StepPins[Z_AXIS][1]->get(), DirectionPins[Z_AXIS][1]->get(), DisablePins[Z_AXIS][1]->get());
|
||||
else
|
||||
myMotor[Z_AXIS][1] = new Motors::Nullmotor(Z2_AXIS);
|
||||
#endif
|
||||
} else {
|
||||
myMotor[Z_AXIS][0] = new Motors::Nullmotor(Z_AXIS);
|
||||
@@ -147,29 +216,52 @@ 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, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN, A_CS_PIN, A_TRINAMIC_DRIVER, A_RSENSE);
|
||||
#elif defined(A_SERVO_PIN)
|
||||
myMotor[A_AXIS][0] = new Motors::RcServo(A_AXIS, A_SERVO_PIN);
|
||||
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 defined(A_UNIPOLAR)
|
||||
myMotor[A_AXIS][0] = new Motors::UnipolarMotor(A_AXIS, A_PIN_PHASE_0, A_PIN_PHASE_1, A_PIN_PHASE_2, A_PIN_PHASE_3);
|
||||
#elif defined(A_STEP_PIN)
|
||||
myMotor[A_AXIS][0] = new Motors::StandardStepper(A_AXIS, A_STEP_PIN, A_DIRECTION_PIN, A_DISABLE_PIN);
|
||||
myMotor[A_AXIS][0] = new Motors::UnipolarMotor(A_AXIS,
|
||||
PhasePins[0][A_AXIS][0]->get(),
|
||||
PhasePins[1][A_AXIS][0]->get(),
|
||||
PhasePins[2][A_AXIS][0]->get(),
|
||||
PhasePins[3][A_AXIS][0]->get());
|
||||
#elif defined(A_DYNAMIXEL_ID)
|
||||
myMotor[A_AXIS][0] = new Motors::Dynamixel2(A_AXIS, A_DYNAMIXEL_ID, DYNAMIXEL_TXD, DYNAMIXEL_RXD, DYNAMIXEL_RTS);
|
||||
myMotor[A_AXIS][0] =
|
||||
new Motors::Dynamixel2(A_AXIS, A_DYNAMIXEL_ID, DynamixelTXDPin->get(), DynamixelRXDPin->get(), DynamixelRTSPin->get());
|
||||
#else
|
||||
myMotor[A_AXIS][0] = new Motors::Nullmotor(A_AXIS);
|
||||
if (ServoPins[A_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[A_AXIS][0] = new Motors::RcServo(A_AXIS, ServoPins[A_AXIS][0]->get());
|
||||
else if (StepPins[A_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[A_AXIS][0] = new Motors::StandardStepper(
|
||||
A_AXIS, StepPins[A_AXIS][0]->get(), DirectionPins[A_AXIS][0]->get(), DisablePins[A_AXIS][0]->get());
|
||||
else
|
||||
myMotor[A_AXIS][0] = new Motors::Nullmotor(A_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef A2_TRINAMIC_DRIVER
|
||||
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 defined(A2_UNIPOLAR)
|
||||
myMotor[A_AXIS][1] = new Motors::UnipolarMotor(A2_AXIS, A2_PIN_PHASE_0, A2_PIN_PHASE_1, A2_PIN_PHASE_2, A2_PIN_PHASE_3);
|
||||
#elif defined(A2_STEP_PIN)
|
||||
myMotor[A_AXIS][1] = new Motors::StandardStepper(A2_AXIS, A2_STEP_PIN, A2_DIRECTION_PIN, A2_DISABLE_PIN);
|
||||
myMotor[A_AXIS][1] = new Motors::UnipolarMotor(A2_AXIS,
|
||||
PhasePins[1][A_AXIS][1]->get(),
|
||||
PhasePins[1][A_AXIS][1]->get(),
|
||||
PhasePins[2][A_AXIS][1]->get(),
|
||||
PhasePins[3][A_AXIS][1]->get());
|
||||
#else
|
||||
myMotor[A_AXIS][1] = new Motors::Nullmotor(A2_AXIS);
|
||||
if (StepPins[A_AXIS][1]->get() != Pin::UNDEFINED)
|
||||
myMotor[A_AXIS][1] = new Motors::StandardStepper(
|
||||
A2_AXIS, StepPins[A_AXIS][1]->get(), DirectionPins[A_AXIS][1]->get(), DisablePins[A_AXIS][1]->get());
|
||||
else
|
||||
myMotor[A_AXIS][1] = new Motors::Nullmotor(A2_AXIS);
|
||||
#endif
|
||||
} else {
|
||||
myMotor[A_AXIS][0] = new Motors::Nullmotor(A_AXIS);
|
||||
@@ -179,29 +271,52 @@ 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, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN, B_CS_PIN, B_TRINAMIC_DRIVER, B_RSENSE);
|
||||
#elif defined(B_SERVO_PIN)
|
||||
myMotor[B_AXIS][0] = new Motors::RcServo(B_AXIS, B_SERVO_PIN);
|
||||
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 defined(B_UNIPOLAR)
|
||||
myMotor[B_AXIS][0] = new Motors::UnipolarMotor(B_AXIS, B_PIN_PHASE_0, B_PIN_PHASE_1, B_PIN_PHASE_2, B_PIN_PHASE_3);
|
||||
#elif defined(B_STEP_PIN)
|
||||
myMotor[B_AXIS][0] = new Motors::StandardStepper(B_AXIS, B_STEP_PIN, B_DIRECTION_PIN, B_DISABLE_PIN);
|
||||
myMotor[B_AXIS][0] = new Motors::UnipolarMotor(B_AXIS,
|
||||
PhasePins[0][B_AXIS][0]->get(),
|
||||
PhasePins[1][B_AXIS][0]->get(),
|
||||
PhasePins[2][B_AXIS][0]->get(),
|
||||
PhasePins[3][B_AXIS][0]->get());
|
||||
#elif defined(B_DYNAMIXEL_ID)
|
||||
myMotor[B_AXIS][0] = new Motors::Dynamixel2(B_AXIS, B_DYNAMIXEL_ID, DYNAMIXEL_TXD, DYNAMIXEL_RXD, DYNAMIXEL_RTS);
|
||||
myMotor[B_AXIS][0] =
|
||||
new Motors::Dynamixel2(B_AXIS, B_DYNAMIXEL_ID, DynamixelTXDPin->get(), DynamixelRXDPin->get(), DynamixelRTSPin->get());
|
||||
#else
|
||||
myMotor[B_AXIS][0] = new Motors::Nullmotor(B_AXIS);
|
||||
if (ServoPins[B_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[B_AXIS][0] = new Motors::RcServo(B_AXIS, ServoPins[B_AXIS][0]->get());
|
||||
else if (StepPins[B_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[B_AXIS][0] = new Motors::StandardStepper(
|
||||
B_AXIS, StepPins[B_AXIS][0]->get(), DirectionPins[B_AXIS][0]->get(), DisablePins[B_AXIS][0]->get());
|
||||
else
|
||||
myMotor[B_AXIS][0] = new Motors::Nullmotor(B_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef B2_TRINAMIC_DRIVER
|
||||
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 defined(B2_UNIPOLAR)
|
||||
myMotor[B_AXIS][1] = new Motors::UnipolarMotor(B2_AXIS, B2_PIN_PHASE_0, B2_PIN_PHASE_1, B2_PIN_PHASE_2, B2_PIN_PHASE_3);
|
||||
#elif defined(B2_STEP_PIN)
|
||||
myMotor[B_AXIS][1] = new Motors::StandardStepper(B2_AXIS, B2_STEP_PIN, B2_DIRECTION_PIN, B2_DISABLE_PIN);
|
||||
myMotor[B_AXIS][1] = new Motors::UnipolarMotor(B2_AXIS,
|
||||
PhasePins[1][B_AXIS][1]->get(),
|
||||
PhasePins[1][B_AXIS][1]->get(),
|
||||
PhasePins[2][B_AXIS][1]->get(),
|
||||
PhasePins[3][B_AXIS][1]->get());
|
||||
#else
|
||||
myMotor[B_AXIS][1] = new Motors::Nullmotor(B2_AXIS);
|
||||
if (StepPins[B_AXIS][1]->get() != Pin::UNDEFINED)
|
||||
myMotor[B_AXIS][1] = new Motors::StandardStepper(
|
||||
B2_AXIS, StepPins[B_AXIS][1]->get(), DirectionPins[B_AXIS][1]->get(), DisablePins[B_AXIS][1]->get());
|
||||
else
|
||||
myMotor[B_AXIS][1] = new Motors::Nullmotor(B2_AXIS);
|
||||
#endif
|
||||
} else {
|
||||
myMotor[B_AXIS][0] = new Motors::Nullmotor(B_AXIS);
|
||||
@@ -211,29 +326,52 @@ 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, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN, C_CS_PIN, C_TRINAMIC_DRIVER, C_RSENSE);
|
||||
#elif defined(C_SERVO_PIN)
|
||||
myMotor[C_AXIS][0] = new Motors::RcServo(C_AXIS, C_SERVO_PIN);
|
||||
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 defined(C_UNIPOLAR)
|
||||
myMotor[C_AXIS][0] = new Motors::UnipolarMotor(C_AXIS, C_PIN_PHASE_0, C_PIN_PHASE_1, C_PIN_PHASE_2, C_PIN_PHASE_3);
|
||||
#elif defined(C_STEP_PIN)
|
||||
myMotor[C_AXIS][0] = new Motors::StandardStepper(C_AXIS, C_STEP_PIN, C_DIRECTION_PIN, C_DISABLE_PIN);
|
||||
myMotor[C_AXIS][0] = new Motors::UnipolarMotor(C_AXIS,
|
||||
PhasePins[0][C_AXIS][0]->get(),
|
||||
PhasePins[1][C_AXIS][0]->get(),
|
||||
PhasePins[2][C_AXIS][0]->get(),
|
||||
PhasePins[3][C_AXIS][0]->get());
|
||||
#elif defined(C_DYNAMIXEL_ID)
|
||||
myMotor[C_AXIS][0] = new Motors::Dynamixel2(C_AXIS, C_DYNAMIXEL_ID, DYNAMIXEL_TXD, DYNAMIXEL_RXD, DYNAMIXEL_RTS);
|
||||
myMotor[C_AXIS][0] =
|
||||
new Motors::Dynamixel2(C_AXIS, C_DYNAMIXEL_ID, DynamixelTXDPin->get(), DynamixelRXDPin->get(), DynamixelRTSPin->get());
|
||||
#else
|
||||
myMotor[C_AXIS][0] = new Motors::Nullmotor(C_AXIS);
|
||||
if (ServoPins[C_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[C_AXIS][0] = new Motors::RcServo(C_AXIS, ServoPins[C_AXIS][0]->get());
|
||||
else if (StepPins[C_AXIS][0]->get() != Pin::UNDEFINED)
|
||||
myMotor[C_AXIS][0] = new Motors::StandardStepper(
|
||||
C_AXIS, StepPins[C_AXIS][0]->get(), DirectionPins[C_AXIS][0]->get(), DisablePins[C_AXIS][0]->get());
|
||||
else
|
||||
myMotor[C_AXIS][0] = new Motors::Nullmotor(C_AXIS);
|
||||
#endif
|
||||
|
||||
#ifdef C2_TRINAMIC_DRIVER
|
||||
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 defined(C2_UNIPOLAR)
|
||||
myMotor[C_AXIS][1] = new Motors::UnipolarMotor(C2_AXIS, C2_PIN_PHASE_0, C2_PIN_PHASE_1, C2_PIN_PHASE_2, C2_PIN_PHASE_3);
|
||||
#elif defined(C2_STEP_PIN)
|
||||
myMotor[C_AXIS][1] = new Motors::StandardStepper(C2_AXIS, C2_STEP_PIN, C2_DIRECTION_PIN, C2_DISABLE_PIN);
|
||||
myMotor[C_AXIS][1] = new Motors::UnipolarMotor(C2_AXIS,
|
||||
PhasePins[1][C_AXIS][1]->get(),
|
||||
PhasePins[1][C_AXIS][1]->get(),
|
||||
PhasePins[2][C_AXIS][1]->get(),
|
||||
PhasePins[3][C_AXIS][1]->get());
|
||||
#else
|
||||
myMotor[C_AXIS][1] = new Motors::Nullmotor(C2_AXIS);
|
||||
if (StepPins[C_AXIS][1]->get() != Pin::UNDEFINED)
|
||||
myMotor[C_AXIS][1] = new Motors::StandardStepper(
|
||||
C2_AXIS, StepPins[C_AXIS][1]->get(), DirectionPins[C_AXIS][1]->get(), DisablePins[C_AXIS][1]->get());
|
||||
else
|
||||
myMotor[C_AXIS][1] = new Motors::Nullmotor(C2_AXIS);
|
||||
#endif
|
||||
} else {
|
||||
myMotor[C_AXIS][0] = new Motors::Nullmotor(C_AXIS);
|
||||
@@ -244,31 +382,32 @@ void init_motors() {
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Using StepStick Mode");
|
||||
|
||||
uint8_t ms3_pins[MAX_N_AXIS][2] = { { X_STEPPER_MS3, X2_STEPPER_MS3 }, { Y_STEPPER_MS3, Y2_STEPPER_MS3 },
|
||||
{ Z_STEPPER_MS3, Z2_STEPPER_MS3 }, { A_STEPPER_MS3, A2_STEPPER_MS3 },
|
||||
{ B_STEPPER_MS3, B2_STEPPER_MS3 }, { C_STEPPER_MS3, C2_STEPPER_MS3 } };
|
||||
Pin ms3_pins[MAX_N_AXIS][2] = { { StepStickMS3[X_AXIS][0]->get(), StepStickMS3[X_AXIS][1]->get() },
|
||||
{ StepStickMS3[Y_AXIS][0]->get(), StepStickMS3[Y_AXIS][1]->get() },
|
||||
{ StepStickMS3[Z_AXIS][0]->get(), StepStickMS3[Z_AXIS][1]->get() },
|
||||
{ StepStickMS3[A_AXIS][0]->get(), StepStickMS3[A_AXIS][1]->get() },
|
||||
{ StepStickMS3[B_AXIS][0]->get(), StepStickMS3[B_AXIS][1]->get() },
|
||||
{ StepStickMS3[C_AXIS][0]->get(), StepStickMS3[C_AXIS][1]->get() } };
|
||||
|
||||
for (int axis = 0; axis < n_axis; axis++) {
|
||||
for (int gang_index = 0; gang_index < 2; gang_index++) {
|
||||
uint8_t pin = ms3_pins[axis][gang_index];
|
||||
if (pin != UNDEFINED_PIN) {
|
||||
digitalWrite(pin, HIGH);
|
||||
pin.setAttr(Pin::Attr::Output);
|
||||
Pin pin = ms3_pins[axis][gang_index];
|
||||
if (pin != Pin::UNDEFINED) {
|
||||
pin.setAttr(Pin::Attr::Output | Pin::Attr::InitialHigh);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
# ifdef STEPPER_RESET
|
||||
// !RESET pin on steppers (MISO On Schematic)
|
||||
digitalWrite(STEPPER_RESET, HIGH);
|
||||
STEPPER_RESET.setAttr(Pin::Attr::Output);
|
||||
# endif
|
||||
if (StepperResetPin->get() != Pin::Undefined) {
|
||||
// !RESET pin on steppers (MISO On Schematic)
|
||||
StepperResetPin->get().setAttr(Pin::Attr::Output | Pin::Attr::InitialHigh);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
if (STEPPERS_DISABLE_PIN != UNDEFINED_PIN) {
|
||||
STEPPERS_DISABLE_PIN.setAttr(Pin::Attr::Output); // global motor enable pin
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Global stepper disable pin:%s", STEPPERS_DISABLE_PIN.name());
|
||||
if (SteppersDisablePin->get() != Pin::UNDEFINED) {
|
||||
SteppersDisablePin->get().setAttr(Pin::Attr::Output); // global motor enable pin
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Global stepper disable pin:%s", SteppersDisablePin->get().name());
|
||||
}
|
||||
|
||||
// certain motors need features to be turned on. Check them here
|
||||
@@ -303,7 +442,7 @@ void motors_set_disable(bool disable) {
|
||||
if (step_enable_invert->get()) {
|
||||
disable = !disable; // Apply pin invert.
|
||||
}
|
||||
digitalWrite(STEPPERS_DISABLE_PIN, disable);
|
||||
SteppersDisablePin->get().write(disable);
|
||||
}
|
||||
|
||||
void motors_read_settings() {
|
||||
@@ -334,7 +473,7 @@ uint8_t motors_set_homing_mode(uint8_t homing_mask, bool isHoming) {
|
||||
|
||||
void motors_step(uint8_t step_mask, uint8_t dir_mask) {
|
||||
auto n_axis = number_axis->get();
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "motors_set_direction_pins:0x%02X", onMask);
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "motors_DirectionPins[set_AXIS][0]->get()s:0x%02X", onMask);
|
||||
|
||||
// Set the direction pins, but optimize for the common
|
||||
// situation where the direction bits haven't changed.
|
||||
|
932
Grbl_Esp32/src/PinSettingsDefinitions.cpp
Normal file
932
Grbl_Esp32/src/PinSettingsDefinitions.cpp
Normal file
@@ -0,0 +1,932 @@
|
||||
// This file attempts to build all the pin settings definitions, while retaining backward compatibility with the
|
||||
// original machine files.
|
||||
//
|
||||
// Note that the source code shouldn't use #define'd pins directly, but always use the settings in the code.
|
||||
// To aid that, I do NOT want to include the default <Arduino.h> from this file (indirectly). Instead, this
|
||||
// file defines the GPIO_NUM_* and I2SO(*) as macro's to strings that the Pin class understands, and uses that.
|
||||
//
|
||||
// To make sure we don't accidentally ripple macro's some place they don't belong, I tried to do this as isolated
|
||||
// as possible.
|
||||
//
|
||||
// NOTE: The order in which defines and includes are used here matters!
|
||||
//
|
||||
// All the preprocessor things are handled first, followed by the real code.
|
||||
|
||||
// First do the defines that take care of GPIO pin name mapping:
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
#define GPIO_NUM_0 "GPIO.0"
|
||||
#define GPIO_NUM_1 "GPIO.1"
|
||||
#define GPIO_NUM_2 "GPIO.2"
|
||||
#define GPIO_NUM_3 "GPIO.3"
|
||||
#define GPIO_NUM_4 "GPIO.4"
|
||||
#define GPIO_NUM_5 "GPIO.5"
|
||||
#define GPIO_NUM_6 "GPIO.6"
|
||||
#define GPIO_NUM_7 "GPIO.7"
|
||||
#define GPIO_NUM_8 "GPIO.8"
|
||||
#define GPIO_NUM_9 "GPIO.9"
|
||||
#define GPIO_NUM_10 "GPIO.10"
|
||||
#define GPIO_NUM_11 "GPIO.11"
|
||||
#define GPIO_NUM_12 "GPIO.12"
|
||||
#define GPIO_NUM_13 "GPIO.13"
|
||||
#define GPIO_NUM_14 "GPIO.14"
|
||||
#define GPIO_NUM_15 "GPIO.15"
|
||||
#define GPIO_NUM_16 "GPIO.16"
|
||||
#define GPIO_NUM_17 "GPIO.17"
|
||||
#define GPIO_NUM_18 "GPIO.18"
|
||||
#define GPIO_NUM_19 "GPIO.19"
|
||||
|
||||
#define GPIO_NUM_21 "GPIO.21"
|
||||
#define GPIO_NUM_22 "GPIO.22"
|
||||
#define GPIO_NUM_23 "GPIO.23"
|
||||
|
||||
#define GPIO_NUM_25 "GPIO.25"
|
||||
#define GPIO_NUM_26 "GPIO.26"
|
||||
#define GPIO_NUM_27 "GPIO.27"
|
||||
|
||||
#define GPIO_NUM_32 "GPIO.32"
|
||||
#define GPIO_NUM_33 "GPIO.33"
|
||||
#define GPIO_NUM_34 "GPIO.34"
|
||||
#define GPIO_NUM_35 "GPIO.35"
|
||||
#define GPIO_NUM_36 "GPIO.36"
|
||||
#define GPIO_NUM_37 "GPIO.37"
|
||||
#define GPIO_NUM_38 "GPIO.38"
|
||||
#define GPIO_NUM_39 "GPIO.39"
|
||||
|
||||
#define UNDEFINED_PIN "undef"
|
||||
|
||||
#define I2SO(n) "I2S." #n
|
||||
|
||||
// Include the file that loads the machine-specific config file.
|
||||
// machine.h must be edited to choose the desired file.
|
||||
#include "Machine.h"
|
||||
|
||||
// machine_common.h contains settings that do not change
|
||||
#include "MachineCommon.h"
|
||||
|
||||
// Update missing definitions with defaults:
|
||||
#include "Defaults.h"
|
||||
|
||||
// Set defaults to all the macro's:
|
||||
#ifndef COOLANT_FLOOD_PIN
|
||||
# define COOLANT_FLOOD_PIN "undef"
|
||||
#endif
|
||||
const char* COOLANT_FLOOD_PIN_DEFAULT = COOLANT_FLOOD_PIN;
|
||||
#ifndef COOLANT_MIST_PIN
|
||||
# define COOLANT_MIST_PIN "undef"
|
||||
#endif
|
||||
const char* COOLANT_MIST_PIN_DEFAULT = COOLANT_MIST_PIN;
|
||||
#ifndef PROBE_PIN
|
||||
# define PROBE_PIN "undef"
|
||||
#endif
|
||||
const char* PROBE_PIN_DEFAULT = PROBE_PIN;
|
||||
#ifndef SDCARD_DET_PIN
|
||||
# define SDCARD_DET_PIN "undef"
|
||||
#endif
|
||||
const char* SDCARD_DET_PIN_DEFAULT = SDCARD_DET_PIN;
|
||||
#ifndef STEPPERS_DISABLE_PIN
|
||||
# define STEPPERS_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* STEPPERS_DISABLE_PIN_DEFAULT = STEPPERS_DISABLE_PIN;
|
||||
#ifndef STEPPER_RESET
|
||||
# define STEPPER_RESET "undef"
|
||||
#endif
|
||||
const char* STEPPER_RESET_DEFAULT = STEPPER_RESET;
|
||||
#ifndef CONTROL_SAFETY_DOOR_PIN
|
||||
# define CONTROL_SAFETY_DOOR_PIN "undef"
|
||||
#endif
|
||||
const char* CONTROL_SAFETY_DOOR_PIN_DEFAULT = CONTROL_SAFETY_DOOR_PIN;
|
||||
#ifndef CONTROL_RESET_PIN
|
||||
# define CONTROL_RESET_PIN "undef"
|
||||
#endif
|
||||
const char* CONTROL_RESET_PIN_DEFAULT = CONTROL_RESET_PIN;
|
||||
#ifndef CONTROL_FEED_HOLD_PIN
|
||||
# define CONTROL_FEED_HOLD_PIN "undef"
|
||||
#endif
|
||||
const char* CONTROL_FEED_HOLD_PIN_DEFAULT = CONTROL_FEED_HOLD_PIN;
|
||||
#ifndef CONTROL_CYCLE_START_PIN
|
||||
# define CONTROL_CYCLE_START_PIN "undef"
|
||||
#endif
|
||||
const char* CONTROL_CYCLE_START_PIN_DEFAULT = CONTROL_CYCLE_START_PIN;
|
||||
#ifndef MACRO_BUTTON_0_PIN
|
||||
# define MACRO_BUTTON_0_PIN "undef"
|
||||
#endif
|
||||
const char* MACRO_BUTTON_0_PIN_DEFAULT = MACRO_BUTTON_0_PIN;
|
||||
#ifndef MACRO_BUTTON_1_PIN
|
||||
# define MACRO_BUTTON_1_PIN "undef"
|
||||
#endif
|
||||
const char* MACRO_BUTTON_1_PIN_DEFAULT = MACRO_BUTTON_1_PIN;
|
||||
#ifndef MACRO_BUTTON_2_PIN
|
||||
# define MACRO_BUTTON_2_PIN "undef"
|
||||
#endif
|
||||
const char* MACRO_BUTTON_2_PIN_DEFAULT = MACRO_BUTTON_2_PIN;
|
||||
#ifndef MACRO_BUTTON_3_PIN
|
||||
# define MACRO_BUTTON_3_PIN "undef"
|
||||
#endif
|
||||
const char* MACRO_BUTTON_3_PIN_DEFAULT = MACRO_BUTTON_3_PIN;
|
||||
#ifndef DYNAMIXEL_TXD
|
||||
# define DYNAMIXEL_TXD "undef"
|
||||
#endif
|
||||
const char* DYNAMIXEL_TXD_DEFAULT = DYNAMIXEL_TXD;
|
||||
#ifndef DYNAMIXEL_RXD
|
||||
# define DYNAMIXEL_RXD "undef"
|
||||
#endif
|
||||
const char* DYNAMIXEL_RXD_DEFAULT = DYNAMIXEL_RXD;
|
||||
#ifndef DYNAMIXEL_RTS
|
||||
# define DYNAMIXEL_RTS "undef"
|
||||
#endif
|
||||
const char* DYNAMIXEL_RTS_DEFAULT = DYNAMIXEL_RTS;
|
||||
|
||||
#ifndef X_LIMIT_PIN
|
||||
# define X_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* X_LIMIT_PIN_DEFAULT = X_LIMIT_PIN;
|
||||
#ifndef X2_LIMIT_PIN
|
||||
# define X2_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* X2_LIMIT_PIN_DEFAULT = X2_LIMIT_PIN;
|
||||
#ifndef Y_LIMIT_PIN
|
||||
# define Y_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* Y_LIMIT_PIN_DEFAULT = Y_LIMIT_PIN;
|
||||
#ifndef Y2_LIMIT_PIN
|
||||
# define Y2_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* Y2_LIMIT_PIN_DEFAULT = Y2_LIMIT_PIN;
|
||||
#ifndef Z_LIMIT_PIN
|
||||
# define Z_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* Z_LIMIT_PIN_DEFAULT = Z_LIMIT_PIN;
|
||||
#ifndef Z2_LIMIT_PIN
|
||||
# define Z2_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* Z2_LIMIT_PIN_DEFAULT = Z2_LIMIT_PIN;
|
||||
#ifndef A_LIMIT_PIN
|
||||
# define A_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* A_LIMIT_PIN_DEFAULT = A_LIMIT_PIN;
|
||||
#ifndef A2_LIMIT_PIN
|
||||
# define A2_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* A2_LIMIT_PIN_DEFAULT = A2_LIMIT_PIN;
|
||||
#ifndef B_LIMIT_PIN
|
||||
# define B_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* B_LIMIT_PIN_DEFAULT = B_LIMIT_PIN;
|
||||
#ifndef B2_LIMIT_PIN
|
||||
# define B2_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* B2_LIMIT_PIN_DEFAULT = B2_LIMIT_PIN;
|
||||
#ifndef C_LIMIT_PIN
|
||||
# define C_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* C_LIMIT_PIN_DEFAULT = C_LIMIT_PIN;
|
||||
#ifndef C2_LIMIT_PIN
|
||||
# define C2_LIMIT_PIN "undef"
|
||||
#endif
|
||||
const char* C2_LIMIT_PIN_DEFAULT = C2_LIMIT_PIN;
|
||||
|
||||
#ifndef X_STEP_PIN
|
||||
# define X_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* X_STEP_PIN_DEFAULT = X_STEP_PIN;
|
||||
#ifndef X2_STEP_PIN
|
||||
# define X2_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* X2_STEP_PIN_DEFAULT = X2_STEP_PIN;
|
||||
#ifndef Y_STEP_PIN
|
||||
# define Y_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* Y_STEP_PIN_DEFAULT = Y_STEP_PIN;
|
||||
#ifndef Y2_STEP_PIN
|
||||
# define Y2_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* Y2_STEP_PIN_DEFAULT = Y2_STEP_PIN;
|
||||
#ifndef Z_STEP_PIN
|
||||
# define Z_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* Z_STEP_PIN_DEFAULT = Z_STEP_PIN;
|
||||
#ifndef Z2_STEP_PIN
|
||||
# define Z2_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* Z2_STEP_PIN_DEFAULT = Z2_STEP_PIN;
|
||||
#ifndef A_STEP_PIN
|
||||
# define A_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* A_STEP_PIN_DEFAULT = A_STEP_PIN;
|
||||
#ifndef A2_STEP_PIN
|
||||
# define A2_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* A2_STEP_PIN_DEFAULT = A2_STEP_PIN;
|
||||
#ifndef B_STEP_PIN
|
||||
# define B_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* B_STEP_PIN_DEFAULT = B_STEP_PIN;
|
||||
#ifndef B2_STEP_PIN
|
||||
# define B2_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* B2_STEP_PIN_DEFAULT = B2_STEP_PIN;
|
||||
#ifndef C_STEP_PIN
|
||||
# define C_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* C_STEP_PIN_DEFAULT = C_STEP_PIN;
|
||||
#ifndef C2_STEP_PIN
|
||||
# define C2_STEP_PIN "undef"
|
||||
#endif
|
||||
const char* C2_STEP_PIN_DEFAULT = C2_STEP_PIN;
|
||||
|
||||
#ifndef X_DIRECTION_PIN
|
||||
# define X_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* X_DIRECTION_PIN_DEFAULT = X_DIRECTION_PIN;
|
||||
#ifndef X2_DIRECTION_PIN
|
||||
# define X2_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* X2_DIRECTION_PIN_DEFAULT = X2_DIRECTION_PIN;
|
||||
#ifndef Y_DIRECTION_PIN
|
||||
# define Y_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* Y_DIRECTION_PIN_DEFAULT = Y_DIRECTION_PIN;
|
||||
#ifndef Y2_DIRECTION_PIN
|
||||
# define Y2_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* Y2_DIRECTION_PIN_DEFAULT = Y2_DIRECTION_PIN;
|
||||
#ifndef Z_DIRECTION_PIN
|
||||
# define Z_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* Z_DIRECTION_PIN_DEFAULT = Z_DIRECTION_PIN;
|
||||
#ifndef Z2_DIRECTION_PIN
|
||||
# define Z2_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* Z2_DIRECTION_PIN_DEFAULT = Z2_DIRECTION_PIN;
|
||||
#ifndef A_DIRECTION_PIN
|
||||
# define A_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* A_DIRECTION_PIN_DEFAULT = A_DIRECTION_PIN;
|
||||
#ifndef A2_DIRECTION_PIN
|
||||
# define A2_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* A2_DIRECTION_PIN_DEFAULT = A2_DIRECTION_PIN;
|
||||
#ifndef B_DIRECTION_PIN
|
||||
# define B_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* B_DIRECTION_PIN_DEFAULT = B_DIRECTION_PIN;
|
||||
#ifndef B2_DIRECTION_PIN
|
||||
# define B2_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* B2_DIRECTION_PIN_DEFAULT = B2_DIRECTION_PIN;
|
||||
#ifndef C_DIRECTION_PIN
|
||||
# define C_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* C_DIRECTION_PIN_DEFAULT = C_DIRECTION_PIN;
|
||||
#ifndef C2_DIRECTION_PIN
|
||||
# define C2_DIRECTION_PIN "undef"
|
||||
#endif
|
||||
const char* C2_DIRECTION_PIN_DEFAULT = C2_DIRECTION_PIN;
|
||||
|
||||
#ifndef X_DISABLE_PIN
|
||||
# define X_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* X_DISABLE_PIN_DEFAULT = X_DISABLE_PIN;
|
||||
#ifndef X2_DISABLE_PIN
|
||||
# define X2_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* X2_DISABLE_PIN_DEFAULT = X2_DISABLE_PIN;
|
||||
#ifndef Y_DISABLE_PIN
|
||||
# define Y_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* Y_DISABLE_PIN_DEFAULT = Y_DISABLE_PIN;
|
||||
#ifndef Y2_DISABLE_PIN
|
||||
# define Y2_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* Y2_DISABLE_PIN_DEFAULT = Y2_DISABLE_PIN;
|
||||
#ifndef Z_DISABLE_PIN
|
||||
# define Z_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* Z_DISABLE_PIN_DEFAULT = Z_DISABLE_PIN;
|
||||
#ifndef Z2_DISABLE_PIN
|
||||
# define Z2_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* Z2_DISABLE_PIN_DEFAULT = Z2_DISABLE_PIN;
|
||||
#ifndef A_DISABLE_PIN
|
||||
# define A_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* A_DISABLE_PIN_DEFAULT = A_DISABLE_PIN;
|
||||
#ifndef A2_DISABLE_PIN
|
||||
# define A2_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* A2_DISABLE_PIN_DEFAULT = A2_DISABLE_PIN;
|
||||
#ifndef B_DISABLE_PIN
|
||||
# define B_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* B_DISABLE_PIN_DEFAULT = B_DISABLE_PIN;
|
||||
#ifndef B2_DISABLE_PIN
|
||||
# define B2_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* B2_DISABLE_PIN_DEFAULT = B2_DISABLE_PIN;
|
||||
#ifndef C_DISABLE_PIN
|
||||
# define C_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* C_DISABLE_PIN_DEFAULT = C_DISABLE_PIN;
|
||||
#ifndef C2_DISABLE_PIN
|
||||
# define C2_DISABLE_PIN "undef"
|
||||
#endif
|
||||
const char* C2_DISABLE_PIN_DEFAULT = C2_DISABLE_PIN;
|
||||
|
||||
#ifndef X_CS_PIN
|
||||
# define X_CS_PIN "undef"
|
||||
#endif
|
||||
const char* X_CS_PIN_DEFAULT = X_CS_PIN;
|
||||
#ifndef X2_CS_PIN
|
||||
# define X2_CS_PIN "undef"
|
||||
#endif
|
||||
const char* X2_CS_PIN_DEFAULT = X2_CS_PIN;
|
||||
#ifndef Y_CS_PIN
|
||||
# define Y_CS_PIN "undef"
|
||||
#endif
|
||||
const char* Y_CS_PIN_DEFAULT = Y_CS_PIN;
|
||||
#ifndef Y2_CS_PIN
|
||||
# define Y2_CS_PIN "undef"
|
||||
#endif
|
||||
const char* Y2_CS_PIN_DEFAULT = Y2_CS_PIN;
|
||||
#ifndef Z_CS_PIN
|
||||
# define Z_CS_PIN "undef"
|
||||
#endif
|
||||
const char* Z_CS_PIN_DEFAULT = Z_CS_PIN;
|
||||
#ifndef Z2_CS_PIN
|
||||
# define Z2_CS_PIN "undef"
|
||||
#endif
|
||||
const char* Z2_CS_PIN_DEFAULT = Z2_CS_PIN;
|
||||
#ifndef A_CS_PIN
|
||||
# define A_CS_PIN "undef"
|
||||
#endif
|
||||
const char* A_CS_PIN_DEFAULT = A_CS_PIN;
|
||||
#ifndef A2_CS_PIN
|
||||
# define A2_CS_PIN "undef"
|
||||
#endif
|
||||
const char* A2_CS_PIN_DEFAULT = A2_CS_PIN;
|
||||
#ifndef B_CS_PIN
|
||||
# define B_CS_PIN "undef"
|
||||
#endif
|
||||
const char* B_CS_PIN_DEFAULT = B_CS_PIN;
|
||||
#ifndef B2_CS_PIN
|
||||
# define B2_CS_PIN "undef"
|
||||
#endif
|
||||
const char* B2_CS_PIN_DEFAULT = B2_CS_PIN;
|
||||
#ifndef C_CS_PIN
|
||||
# define C_CS_PIN "undef"
|
||||
#endif
|
||||
const char* C_CS_PIN_DEFAULT = C_CS_PIN;
|
||||
#ifndef C2_CS_PIN
|
||||
# define C2_CS_PIN "undef"
|
||||
#endif
|
||||
const char* C2_CS_PIN_DEFAULT = C2_CS_PIN;
|
||||
|
||||
#ifndef X_SERVO_PIN
|
||||
# define X_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* X_SERVO_PIN_DEFAULT = X_SERVO_PIN;
|
||||
#ifndef X2_SERVO_PIN
|
||||
# define X2_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* X2_SERVO_PIN_DEFAULT = X2_SERVO_PIN;
|
||||
#ifndef Y_SERVO_PIN
|
||||
# define Y_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* Y_SERVO_PIN_DEFAULT = Y_SERVO_PIN;
|
||||
#ifndef Y2_SERVO_PIN
|
||||
# define Y2_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* Y2_SERVO_PIN_DEFAULT = Y2_SERVO_PIN;
|
||||
#ifndef Z_SERVO_PIN
|
||||
# define Z_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* Z_SERVO_PIN_DEFAULT = Z_SERVO_PIN;
|
||||
#ifndef Z2_SERVO_PIN
|
||||
# define Z2_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* Z2_SERVO_PIN_DEFAULT = Z2_SERVO_PIN;
|
||||
#ifndef A_SERVO_PIN
|
||||
# define A_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* A_SERVO_PIN_DEFAULT = A_SERVO_PIN;
|
||||
#ifndef A2_SERVO_PIN
|
||||
# define A2_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* A2_SERVO_PIN_DEFAULT = A2_SERVO_PIN;
|
||||
#ifndef B_SERVO_PIN
|
||||
# define B_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* B_SERVO_PIN_DEFAULT = B_SERVO_PIN;
|
||||
#ifndef B2_SERVO_PIN
|
||||
# define B2_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* B2_SERVO_PIN_DEFAULT = B2_SERVO_PIN;
|
||||
#ifndef C_SERVO_PIN
|
||||
# define C_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* C_SERVO_PIN_DEFAULT = C_SERVO_PIN;
|
||||
#ifndef C2_SERVO_PIN
|
||||
# define C2_SERVO_PIN "undef"
|
||||
#endif
|
||||
const char* C2_SERVO_PIN_DEFAULT = C2_SERVO_PIN;
|
||||
|
||||
#ifndef X_STEPPER_MS3
|
||||
# define X_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* X_STEPPER_MS3_DEFAULT = X_STEPPER_MS3;
|
||||
#ifndef X2_STEPPER_MS3
|
||||
# define X2_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* X2_STEPPER_MS3_DEFAULT = X2_STEPPER_MS3;
|
||||
#ifndef Y_STEPPER_MS3
|
||||
# define Y_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* Y_STEPPER_MS3_DEFAULT = Y_STEPPER_MS3;
|
||||
#ifndef Y2_STEPPER_MS3
|
||||
# define Y2_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* Y2_STEPPER_MS3_DEFAULT = Y2_STEPPER_MS3;
|
||||
#ifndef Z_STEPPER_MS3
|
||||
# define Z_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* Z_STEPPER_MS3_DEFAULT = Z_STEPPER_MS3;
|
||||
#ifndef Z2_STEPPER_MS3
|
||||
# define Z2_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* Z2_STEPPER_MS3_DEFAULT = Z2_STEPPER_MS3;
|
||||
#ifndef A_STEPPER_MS3
|
||||
# define A_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* A_STEPPER_MS3_DEFAULT = A_STEPPER_MS3;
|
||||
#ifndef A2_STEPPER_MS3
|
||||
# define A2_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* A2_STEPPER_MS3_DEFAULT = A2_STEPPER_MS3;
|
||||
#ifndef B_STEPPER_MS3
|
||||
# define B_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* B_STEPPER_MS3_DEFAULT = B_STEPPER_MS3;
|
||||
#ifndef B2_STEPPER_MS3
|
||||
# define B2_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* B2_STEPPER_MS3_DEFAULT = B2_STEPPER_MS3;
|
||||
#ifndef C_STEPPER_MS3
|
||||
# define C_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* C_STEPPER_MS3_DEFAULT = C_STEPPER_MS3;
|
||||
#ifndef C2_STEPPER_MS3
|
||||
# define C2_STEPPER_MS3 "undef"
|
||||
#endif
|
||||
const char* C2_STEPPER_MS3_DEFAULT = C2_STEPPER_MS3;
|
||||
|
||||
#ifndef X_PIN_PHASE_0
|
||||
# define X_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* X_PIN_PHASE_0_DEFAULT = X_PIN_PHASE_0;
|
||||
#ifndef X2_PIN_PHASE_0
|
||||
# define X2_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* X2_PIN_PHASE_0_DEFAULT = X2_PIN_PHASE_0;
|
||||
#ifndef Y_PIN_PHASE_0
|
||||
# define Y_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* Y_PIN_PHASE_0_DEFAULT = Y_PIN_PHASE_0;
|
||||
#ifndef Y2_PIN_PHASE_0
|
||||
# define Y2_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* Y2_PIN_PHASE_0_DEFAULT = Y2_PIN_PHASE_0;
|
||||
#ifndef Z_PIN_PHASE_0
|
||||
# define Z_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* Z_PIN_PHASE_0_DEFAULT = Z_PIN_PHASE_0;
|
||||
#ifndef Z2_PIN_PHASE_0
|
||||
# define Z2_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* Z2_PIN_PHASE_0_DEFAULT = Z2_PIN_PHASE_0;
|
||||
#ifndef A_PIN_PHASE_0
|
||||
# define A_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* A_PIN_PHASE_0_DEFAULT = A_PIN_PHASE_0;
|
||||
#ifndef A2_PIN_PHASE_0
|
||||
# define A2_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* A2_PIN_PHASE_0_DEFAULT = A2_PIN_PHASE_0;
|
||||
#ifndef B_PIN_PHASE_0
|
||||
# define B_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* B_PIN_PHASE_0_DEFAULT = B_PIN_PHASE_0;
|
||||
#ifndef B2_PIN_PHASE_0
|
||||
# define B2_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* B2_PIN_PHASE_0_DEFAULT = B2_PIN_PHASE_0;
|
||||
#ifndef C_PIN_PHASE_0
|
||||
# define C_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* C_PIN_PHASE_0_DEFAULT = C_PIN_PHASE_0;
|
||||
#ifndef C2_PIN_PHASE_0
|
||||
# define C2_PIN_PHASE_0 "undef"
|
||||
#endif
|
||||
const char* C2_PIN_PHASE_0_DEFAULT = C2_PIN_PHASE_0;
|
||||
|
||||
#ifndef X_PIN_PHASE_1
|
||||
# define X_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* X_PIN_PHASE_1_DEFAULT = X_PIN_PHASE_1;
|
||||
#ifndef X2_PIN_PHASE_1
|
||||
# define X2_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* X2_PIN_PHASE_1_DEFAULT = X2_PIN_PHASE_1;
|
||||
#ifndef Y_PIN_PHASE_1
|
||||
# define Y_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* Y_PIN_PHASE_1_DEFAULT = Y_PIN_PHASE_1;
|
||||
#ifndef Y2_PIN_PHASE_1
|
||||
# define Y2_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* Y2_PIN_PHASE_1_DEFAULT = Y2_PIN_PHASE_1;
|
||||
#ifndef Z_PIN_PHASE_1
|
||||
# define Z_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* Z_PIN_PHASE_1_DEFAULT = Z_PIN_PHASE_1;
|
||||
#ifndef Z2_PIN_PHASE_1
|
||||
# define Z2_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* Z2_PIN_PHASE_1_DEFAULT = Z2_PIN_PHASE_1;
|
||||
#ifndef A_PIN_PHASE_1
|
||||
# define A_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* A_PIN_PHASE_1_DEFAULT = A_PIN_PHASE_1;
|
||||
#ifndef A2_PIN_PHASE_1
|
||||
# define A2_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* A2_PIN_PHASE_1_DEFAULT = A2_PIN_PHASE_1;
|
||||
#ifndef B_PIN_PHASE_1
|
||||
# define B_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* B_PIN_PHASE_1_DEFAULT = B_PIN_PHASE_1;
|
||||
#ifndef B2_PIN_PHASE_1
|
||||
# define B2_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* B2_PIN_PHASE_1_DEFAULT = B2_PIN_PHASE_1;
|
||||
#ifndef C_PIN_PHASE_1
|
||||
# define C_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* C_PIN_PHASE_1_DEFAULT = C_PIN_PHASE_1;
|
||||
#ifndef C2_PIN_PHASE_1
|
||||
# define C2_PIN_PHASE_1 "undef"
|
||||
#endif
|
||||
const char* C2_PIN_PHASE_1_DEFAULT = C2_PIN_PHASE_1;
|
||||
|
||||
#ifndef X_PIN_PHASE_2
|
||||
# define X_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* X_PIN_PHASE_2_DEFAULT = X_PIN_PHASE_2;
|
||||
#ifndef X2_PIN_PHASE_2
|
||||
# define X2_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* X2_PIN_PHASE_2_DEFAULT = X2_PIN_PHASE_2;
|
||||
#ifndef Y_PIN_PHASE_2
|
||||
# define Y_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* Y_PIN_PHASE_2_DEFAULT = Y_PIN_PHASE_2;
|
||||
#ifndef Y2_PIN_PHASE_2
|
||||
# define Y2_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* Y2_PIN_PHASE_2_DEFAULT = Y2_PIN_PHASE_2;
|
||||
#ifndef Z_PIN_PHASE_2
|
||||
# define Z_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* Z_PIN_PHASE_2_DEFAULT = Z_PIN_PHASE_2;
|
||||
#ifndef Z2_PIN_PHASE_2
|
||||
# define Z2_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* Z2_PIN_PHASE_2_DEFAULT = Z2_PIN_PHASE_2;
|
||||
#ifndef A_PIN_PHASE_2
|
||||
# define A_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* A_PIN_PHASE_2_DEFAULT = A_PIN_PHASE_2;
|
||||
#ifndef A2_PIN_PHASE_2
|
||||
# define A2_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* A2_PIN_PHASE_2_DEFAULT = A2_PIN_PHASE_2;
|
||||
#ifndef B_PIN_PHASE_2
|
||||
# define B_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* B_PIN_PHASE_2_DEFAULT = B_PIN_PHASE_2;
|
||||
#ifndef B2_PIN_PHASE_2
|
||||
# define B2_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* B2_PIN_PHASE_2_DEFAULT = B2_PIN_PHASE_2;
|
||||
#ifndef C_PIN_PHASE_2
|
||||
# define C_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* C_PIN_PHASE_2_DEFAULT = C_PIN_PHASE_2;
|
||||
#ifndef C2_PIN_PHASE_2
|
||||
# define C2_PIN_PHASE_2 "undef"
|
||||
#endif
|
||||
const char* C2_PIN_PHASE_2_DEFAULT = C2_PIN_PHASE_2;
|
||||
|
||||
#ifndef X_PIN_PHASE_3
|
||||
# define X_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* X_PIN_PHASE_3_DEFAULT = X_PIN_PHASE_3;
|
||||
#ifndef X2_PIN_PHASE_3
|
||||
# define X2_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* X2_PIN_PHASE_3_DEFAULT = X2_PIN_PHASE_3;
|
||||
#ifndef Y_PIN_PHASE_3
|
||||
# define Y_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* Y_PIN_PHASE_3_DEFAULT = Y_PIN_PHASE_3;
|
||||
#ifndef Y2_PIN_PHASE_3
|
||||
# define Y2_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* Y2_PIN_PHASE_3_DEFAULT = Y2_PIN_PHASE_3;
|
||||
#ifndef Z_PIN_PHASE_3
|
||||
# define Z_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* Z_PIN_PHASE_3_DEFAULT = Z_PIN_PHASE_3;
|
||||
#ifndef Z2_PIN_PHASE_3
|
||||
# define Z2_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* Z2_PIN_PHASE_3_DEFAULT = Z2_PIN_PHASE_3;
|
||||
#ifndef A_PIN_PHASE_3
|
||||
# define A_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* A_PIN_PHASE_3_DEFAULT = A_PIN_PHASE_3;
|
||||
#ifndef A2_PIN_PHASE_3
|
||||
# define A2_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* A2_PIN_PHASE_3_DEFAULT = A2_PIN_PHASE_3;
|
||||
#ifndef B_PIN_PHASE_3
|
||||
# define B_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* B_PIN_PHASE_3_DEFAULT = B_PIN_PHASE_3;
|
||||
#ifndef B2_PIN_PHASE_3
|
||||
# define B2_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* B2_PIN_PHASE_3_DEFAULT = B2_PIN_PHASE_3;
|
||||
#ifndef C_PIN_PHASE_3
|
||||
# define C_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* C_PIN_PHASE_3_DEFAULT = C_PIN_PHASE_3;
|
||||
#ifndef C2_PIN_PHASE_3
|
||||
# define C2_PIN_PHASE_3 "undef"
|
||||
#endif
|
||||
const char* C2_PIN_PHASE_3_DEFAULT = C2_PIN_PHASE_3;
|
||||
|
||||
// We have all the defaults we need at this point. Settings will include Arduino, so we have to get
|
||||
// rid of the defines we made earlier:
|
||||
#undef GPIO_NUM_0
|
||||
#undef GPIO_NUM_1
|
||||
#undef GPIO_NUM_2
|
||||
#undef GPIO_NUM_3
|
||||
#undef GPIO_NUM_4
|
||||
#undef GPIO_NUM_5
|
||||
#undef GPIO_NUM_6
|
||||
#undef GPIO_NUM_7
|
||||
#undef GPIO_NUM_8
|
||||
#undef GPIO_NUM_9
|
||||
#undef GPIO_NUM_10
|
||||
#undef GPIO_NUM_11
|
||||
#undef GPIO_NUM_12
|
||||
#undef GPIO_NUM_13
|
||||
#undef GPIO_NUM_14
|
||||
#undef GPIO_NUM_15
|
||||
#undef GPIO_NUM_16
|
||||
#undef GPIO_NUM_17
|
||||
#undef GPIO_NUM_18
|
||||
#undef GPIO_NUM_19
|
||||
|
||||
#undef GPIO_NUM_21
|
||||
#undef GPIO_NUM_22
|
||||
#undef GPIO_NUM_23
|
||||
|
||||
#undef GPIO_NUM_25
|
||||
#undef GPIO_NUM_26
|
||||
#undef GPIO_NUM_27
|
||||
|
||||
#undef GPIO_NUM_32
|
||||
#undef GPIO_NUM_33
|
||||
#undef GPIO_NUM_34
|
||||
#undef GPIO_NUM_35
|
||||
#undef GPIO_NUM_36
|
||||
#undef GPIO_NUM_37
|
||||
#undef GPIO_NUM_38
|
||||
#undef GPIO_NUM_39
|
||||
#undef I2SO
|
||||
|
||||
// We need settings.h for the settings classes
|
||||
#include "Grbl.h"
|
||||
#include "Settings.h"
|
||||
#include "SettingsDefinitions.h"
|
||||
|
||||
// Define the pins:
|
||||
|
||||
PinSetting* CoolantFloodPin; // COOLANT_FLOOD_PIN
|
||||
PinSetting* CoolantMistPin; // COOLANT_MIST_PIN
|
||||
PinSetting* ProbePin; // PROBE_PIN
|
||||
PinSetting* SDCardDetPin; // SDCARD_DET_PIN
|
||||
PinSetting* SteppersDisablePin; // STEPPERS_DISABLE_PIN
|
||||
PinSetting* StepperResetPin; // STEPPER_RESET
|
||||
PinSetting* ControlSafetyDoorPin; // CONTROL_SAFETY_DOOR_PIN
|
||||
PinSetting* ControlResetPin; // CONTROL_RESET_PIN
|
||||
PinSetting* ControlFeedHoldPin; // CONTROL_FEED_HOLD_PIN
|
||||
PinSetting* ControlCycleStartPin; // CONTROL_CYCLE_START_PIN
|
||||
PinSetting* MacroButton0Pin; // MACRO_BUTTON_0_PIN
|
||||
PinSetting* MacroButton1Pin; // MACRO_BUTTON_1_PIN
|
||||
PinSetting* MacroButton2Pin; // MACRO_BUTTON_2_PIN
|
||||
PinSetting* MacroButton3Pin; // MACRO_BUTTON_3_PIN
|
||||
|
||||
PinSetting* DynamixelTXDPin; // DYNAMIXEL_TXD
|
||||
PinSetting* DynamixelRXDPin; // DYNAMIXEL_RXD
|
||||
PinSetting* DynamixelRTSPin; // DYNAMIXEL_RTS
|
||||
|
||||
PinSetting* UserDigitalPin[4];
|
||||
PinSetting* UserAnalogPin[4];
|
||||
|
||||
PinSetting* LimitPins[MAX_N_AXIS][2];
|
||||
PinSetting* StepPins[MAX_N_AXIS][2];
|
||||
PinSetting* DirectionPins[MAX_N_AXIS][2];
|
||||
PinSetting* DisablePins[MAX_N_AXIS][2];
|
||||
PinSetting* ClearToSendPins[MAX_N_AXIS][2];
|
||||
PinSetting* ServoPins[MAX_N_AXIS][2];
|
||||
PinSetting* StepStickMS3[MAX_N_AXIS][2];
|
||||
PinSetting* PhasePins[4][MAX_N_AXIS][2];
|
||||
|
||||
// Initialize the pin settings
|
||||
void make_pin_settings() {
|
||||
CoolantFloodPin = new PinSetting("Pins/CoolantFlood", COOLANT_FLOOD_PIN_DEFAULT);
|
||||
CoolantMistPin = new PinSetting("Pins/CoolantMist", COOLANT_MIST_PIN_DEFAULT);
|
||||
ProbePin = new PinSetting("Pins/Probe", PROBE_PIN_DEFAULT);
|
||||
SDCardDetPin = new PinSetting("Pins/SDCardDet", SDCARD_DET_PIN_DEFAULT);
|
||||
SteppersDisablePin = new PinSetting("Pins/SteppersDisable", STEPPERS_DISABLE_PIN_DEFAULT);
|
||||
StepperResetPin = new PinSetting("Pins/SteppersReset", STEPPER_RESET_DEFAULT);
|
||||
ControlSafetyDoorPin = new PinSetting("Pins/ControlSafetyDoor", CONTROL_SAFETY_DOOR_PIN_DEFAULT);
|
||||
ControlResetPin = new PinSetting("Pins/ControlReset", CONTROL_RESET_PIN_DEFAULT);
|
||||
ControlFeedHoldPin = new PinSetting("Pins/ControlFeedHold", CONTROL_FEED_HOLD_PIN_DEFAULT);
|
||||
ControlCycleStartPin = new PinSetting("Pins/ControlCycleStart", CONTROL_CYCLE_START_PIN_DEFAULT);
|
||||
MacroButton0Pin = new PinSetting("Pins/MacroButton0", MACRO_BUTTON_0_PIN_DEFAULT);
|
||||
MacroButton1Pin = new PinSetting("Pins/MacroButton1", MACRO_BUTTON_1_PIN_DEFAULT);
|
||||
MacroButton2Pin = new PinSetting("Pins/MacroButton2", MACRO_BUTTON_2_PIN_DEFAULT);
|
||||
MacroButton3Pin = new PinSetting("Pins/MacroButton3", MACRO_BUTTON_3_PIN_DEFAULT);
|
||||
DynamixelTXDPin = new PinSetting("Pins/DynamixelTXD", DYNAMIXEL_TXD_DEFAULT);
|
||||
DynamixelRXDPin = new PinSetting("Pins/DynamixelRXD", DYNAMIXEL_RXD_DEFAULT);
|
||||
DynamixelRTSPin = new PinSetting("Pins/DynamixelRTS", DYNAMIXEL_RTS_DEFAULT);
|
||||
|
||||
// User pins:
|
||||
UserDigitalPin[0] = new PinSetting("Pins/UserDigital/0", USER_DIGITAL_PIN_0);
|
||||
UserAnalogPin[0] = new PinSetting("Pins/UserAnalog/0", USER_ANALOG_PIN_0);
|
||||
UserDigitalPin[1] = new PinSetting("Pins/UserDigital/1", USER_DIGITAL_PIN_1);
|
||||
UserAnalogPin[1] = new PinSetting("Pins/UserAnalog/1", USER_ANALOG_PIN_1);
|
||||
UserDigitalPin[2] = new PinSetting("Pins/UserDigital/2", USER_DIGITAL_PIN_2);
|
||||
UserAnalogPin[2] = new PinSetting("Pins/UserAnalog/2", USER_ANALOG_PIN_2);
|
||||
UserDigitalPin[3] = new PinSetting("Pins/UserDigital/3", USER_DIGITAL_PIN_3);
|
||||
UserAnalogPin[3] = new PinSetting("Pins/UserAnalog/3", USER_ANALOG_PIN_3);
|
||||
|
||||
// Axis:
|
||||
LimitPins[X_AXIS][0] = new PinSetting("Pins/X/Limit", X_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[X_AXIS][1] = new PinSetting("Pins/X2/Limit", X2_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[Y_AXIS][0] = new PinSetting("Pins/Y/Limit", Y_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[Y_AXIS][1] = new PinSetting("Pins/Y2/Limit", Y2_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[Z_AXIS][0] = new PinSetting("Pins/Z/Limit", Z_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[Z_AXIS][1] = new PinSetting("Pins/Z2/Limit", Z2_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[A_AXIS][0] = new PinSetting("Pins/A/Limit", A_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[A_AXIS][1] = new PinSetting("Pins/A2/Limit", A2_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[B_AXIS][0] = new PinSetting("Pins/B/Limit", B_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[B_AXIS][1] = new PinSetting("Pins/B2/Limit", B2_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[C_AXIS][0] = new PinSetting("Pins/C/Limit", C_LIMIT_PIN_DEFAULT);
|
||||
LimitPins[C_AXIS][1] = new PinSetting("Pins/C2/Limit", C2_LIMIT_PIN_DEFAULT);
|
||||
|
||||
StepPins[X_AXIS][0] = new PinSetting("Pins/X/Step", X_STEP_PIN_DEFAULT);
|
||||
StepPins[X_AXIS][1] = new PinSetting("Pins/X2/Step", X2_STEP_PIN_DEFAULT);
|
||||
StepPins[Y_AXIS][0] = new PinSetting("Pins/Y/Step", Y_STEP_PIN_DEFAULT);
|
||||
StepPins[Y_AXIS][1] = new PinSetting("Pins/Y2/Step", Y2_STEP_PIN_DEFAULT);
|
||||
StepPins[Z_AXIS][0] = new PinSetting("Pins/Z/Step", Z_STEP_PIN_DEFAULT);
|
||||
StepPins[Z_AXIS][1] = new PinSetting("Pins/Z2/Step", Z2_STEP_PIN_DEFAULT);
|
||||
StepPins[A_AXIS][0] = new PinSetting("Pins/A/Step", A_STEP_PIN_DEFAULT);
|
||||
StepPins[A_AXIS][1] = new PinSetting("Pins/A2/Step", A2_STEP_PIN_DEFAULT);
|
||||
StepPins[B_AXIS][0] = new PinSetting("Pins/B/Step", B_STEP_PIN_DEFAULT);
|
||||
StepPins[B_AXIS][1] = new PinSetting("Pins/B2/Step", B2_STEP_PIN_DEFAULT);
|
||||
StepPins[C_AXIS][0] = new PinSetting("Pins/C/Step", C_STEP_PIN_DEFAULT);
|
||||
StepPins[C_AXIS][1] = new PinSetting("Pins/C2/Step", C2_STEP_PIN_DEFAULT);
|
||||
|
||||
DirectionPins[X_AXIS][0] = new PinSetting("Pins/X/Direction", X_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[X_AXIS][1] = new PinSetting("Pins/X2/Direction", X2_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[Y_AXIS][0] = new PinSetting("Pins/Y/Direction", Y_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[Y_AXIS][1] = new PinSetting("Pins/Y2/Direction", Y2_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[Z_AXIS][0] = new PinSetting("Pins/Z/Direction", Z_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[Z_AXIS][1] = new PinSetting("Pins/Z2/Direction", Z2_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[A_AXIS][0] = new PinSetting("Pins/A/Direction", A_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[A_AXIS][1] = new PinSetting("Pins/A2/Direction", A2_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[B_AXIS][0] = new PinSetting("Pins/B/Direction", B_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[B_AXIS][1] = new PinSetting("Pins/B2/Direction", B2_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[C_AXIS][0] = new PinSetting("Pins/C/Direction", C_DIRECTION_PIN_DEFAULT);
|
||||
DirectionPins[C_AXIS][1] = new PinSetting("Pins/C2/Direction", C2_DIRECTION_PIN_DEFAULT);
|
||||
|
||||
DisablePins[X_AXIS][0] = new PinSetting("Pins/X/Disable", X_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[X_AXIS][1] = new PinSetting("Pins/X2/Disable", X2_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[Y_AXIS][0] = new PinSetting("Pins/Y/Disable", Y_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[Y_AXIS][1] = new PinSetting("Pins/Y2/Disable", Y2_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[Z_AXIS][0] = new PinSetting("Pins/Z/Disable", Z_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[Z_AXIS][1] = new PinSetting("Pins/Z2/Disable", Z2_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[A_AXIS][0] = new PinSetting("Pins/A/Disable", A_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[A_AXIS][1] = new PinSetting("Pins/A2/Disable", A2_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[B_AXIS][0] = new PinSetting("Pins/B/Disable", B_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[B_AXIS][1] = new PinSetting("Pins/B2/Disable", B2_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[C_AXIS][0] = new PinSetting("Pins/C/Disable", C_DISABLE_PIN_DEFAULT);
|
||||
DisablePins[C_AXIS][1] = new PinSetting("Pins/C2/Disable", C2_DISABLE_PIN_DEFAULT);
|
||||
|
||||
ClearToSendPins[X_AXIS][0] = new PinSetting("Pins/X/ClearToSend", X_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[X_AXIS][1] = new PinSetting("Pins/X2/ClearToSend", X2_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[Y_AXIS][0] = new PinSetting("Pins/Y/ClearToSend", Y_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[Y_AXIS][1] = new PinSetting("Pins/Y2/ClearToSend", Y2_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[Z_AXIS][0] = new PinSetting("Pins/Z/ClearToSend", Z_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[Z_AXIS][1] = new PinSetting("Pins/Z2/ClearToSend", Z2_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[A_AXIS][0] = new PinSetting("Pins/A/ClearToSend", A_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[A_AXIS][1] = new PinSetting("Pins/A2/ClearToSend", A2_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[B_AXIS][0] = new PinSetting("Pins/B/ClearToSend", B_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[B_AXIS][1] = new PinSetting("Pins/B2/ClearToSend", B2_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[C_AXIS][0] = new PinSetting("Pins/C/ClearToSend", C_CS_PIN_DEFAULT);
|
||||
ClearToSendPins[C_AXIS][1] = new PinSetting("Pins/C2/ClearToSend", C2_CS_PIN_DEFAULT);
|
||||
|
||||
ServoPins[X_AXIS][0] = new PinSetting("Pins/X/ServoPins", X_SERVO_PIN_DEFAULT);
|
||||
ServoPins[X_AXIS][1] = new PinSetting("Pins/X2/ServoPins", X2_SERVO_PIN_DEFAULT);
|
||||
ServoPins[Y_AXIS][0] = new PinSetting("Pins/Y/ServoPins", Y_SERVO_PIN_DEFAULT);
|
||||
ServoPins[Y_AXIS][1] = new PinSetting("Pins/Y2/ServoPins", Y2_SERVO_PIN_DEFAULT);
|
||||
ServoPins[Z_AXIS][0] = new PinSetting("Pins/Z/ServoPins", Z_SERVO_PIN_DEFAULT);
|
||||
ServoPins[Z_AXIS][1] = new PinSetting("Pins/Z2/ServoPins", Z2_SERVO_PIN_DEFAULT);
|
||||
ServoPins[A_AXIS][0] = new PinSetting("Pins/A/ServoPins", A_SERVO_PIN_DEFAULT);
|
||||
ServoPins[A_AXIS][1] = new PinSetting("Pins/A2/ServoPins", A2_SERVO_PIN_DEFAULT);
|
||||
ServoPins[B_AXIS][0] = new PinSetting("Pins/B/ServoPins", B_SERVO_PIN_DEFAULT);
|
||||
ServoPins[B_AXIS][1] = new PinSetting("Pins/B2/ServoPins", B2_SERVO_PIN_DEFAULT);
|
||||
ServoPins[C_AXIS][0] = new PinSetting("Pins/C/ServoPins", C_SERVO_PIN_DEFAULT);
|
||||
ServoPins[C_AXIS][1] = new PinSetting("Pins/C2/ServoPins", C2_SERVO_PIN_DEFAULT);
|
||||
|
||||
StepStickMS3[X_AXIS][0] = new PinSetting("Pins/X/StepStickMS3", X_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[X_AXIS][1] = new PinSetting("Pins/X2/StepStickMS3", X2_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[Y_AXIS][0] = new PinSetting("Pins/Y/StepStickMS3", Y_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[Y_AXIS][1] = new PinSetting("Pins/Y2/StepStickMS3", Y2_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[Z_AXIS][0] = new PinSetting("Pins/Z/StepStickMS3", Z_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[Z_AXIS][1] = new PinSetting("Pins/Z2/StepStickMS3", Z2_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[A_AXIS][0] = new PinSetting("Pins/A/StepStickMS3", A_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[A_AXIS][1] = new PinSetting("Pins/A2/StepStickMS3", A2_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[B_AXIS][0] = new PinSetting("Pins/B/StepStickMS3", B_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[B_AXIS][1] = new PinSetting("Pins/B2/StepStickMS3", B2_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[C_AXIS][0] = new PinSetting("Pins/C/StepStickMS3", C_STEPPER_MS3_DEFAULT);
|
||||
StepStickMS3[C_AXIS][1] = new PinSetting("Pins/C2/StepStickMS3", C2_STEPPER_MS3_DEFAULT);
|
||||
|
||||
PhasePins[0][X_AXIS][0] = new PinSetting("Pins/X/Phase0", X_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][X_AXIS][1] = new PinSetting("Pins/X2/Phase0", X2_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][Y_AXIS][0] = new PinSetting("Pins/Y/Phase0", Y_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][Y_AXIS][1] = new PinSetting("Pins/Y2/Phase0", Y2_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][Z_AXIS][0] = new PinSetting("Pins/Z/Phase0", Z_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][Z_AXIS][1] = new PinSetting("Pins/Z2/Phase0", Z2_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][A_AXIS][0] = new PinSetting("Pins/A/Phase0", A_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][A_AXIS][1] = new PinSetting("Pins/A2/Phase0", A2_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][B_AXIS][0] = new PinSetting("Pins/B/Phase0", B_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][B_AXIS][1] = new PinSetting("Pins/B2/Phase0", B2_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][C_AXIS][0] = new PinSetting("Pins/C/Phase0", C_PIN_PHASE_0_DEFAULT);
|
||||
PhasePins[0][C_AXIS][1] = new PinSetting("Pins/C2/Phase0", C2_PIN_PHASE_0_DEFAULT);
|
||||
|
||||
PhasePins[1][X_AXIS][0] = new PinSetting("Pins/X/Phase1", X_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][X_AXIS][1] = new PinSetting("Pins/X2/Phase1", X2_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][Y_AXIS][0] = new PinSetting("Pins/Y/Phase1", Y_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][Y_AXIS][1] = new PinSetting("Pins/Y2/Phase1", Y2_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][Z_AXIS][0] = new PinSetting("Pins/Z/Phase1", Z_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][Z_AXIS][1] = new PinSetting("Pins/Z2/Phase1", Z2_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][A_AXIS][0] = new PinSetting("Pins/A/Phase1", A_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][A_AXIS][1] = new PinSetting("Pins/A2/Phase1", A2_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][B_AXIS][0] = new PinSetting("Pins/B/Phase1", B_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][B_AXIS][1] = new PinSetting("Pins/B2/Phase1", B2_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][C_AXIS][0] = new PinSetting("Pins/C/Phase1", C_PIN_PHASE_1_DEFAULT);
|
||||
PhasePins[1][C_AXIS][1] = new PinSetting("Pins/C2/Phase1", C2_PIN_PHASE_1_DEFAULT);
|
||||
|
||||
PhasePins[2][X_AXIS][0] = new PinSetting("Pins/X/Phase2", X_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][X_AXIS][1] = new PinSetting("Pins/X2/Phase2", X2_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][Y_AXIS][0] = new PinSetting("Pins/Y/Phase2", Y_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][Y_AXIS][1] = new PinSetting("Pins/Y2/Phase2", Y2_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][Z_AXIS][0] = new PinSetting("Pins/Z/Phase2", Z_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][Z_AXIS][1] = new PinSetting("Pins/Z2/Phase2", Z2_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][A_AXIS][0] = new PinSetting("Pins/A/Phase2", A_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][A_AXIS][1] = new PinSetting("Pins/A2/Phase2", A2_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][B_AXIS][0] = new PinSetting("Pins/B/Phase2", B_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][B_AXIS][1] = new PinSetting("Pins/B2/Phase2", B2_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][C_AXIS][0] = new PinSetting("Pins/C/Phase2", C_PIN_PHASE_2_DEFAULT);
|
||||
PhasePins[2][C_AXIS][1] = new PinSetting("Pins/C2/Phase2", C2_PIN_PHASE_2_DEFAULT);
|
||||
|
||||
PhasePins[3][X_AXIS][0] = new PinSetting("Pins/X/Phase3", X_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][X_AXIS][1] = new PinSetting("Pins/X2/Phase3", X2_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][Y_AXIS][0] = new PinSetting("Pins/Y/Phase3", Y_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][Y_AXIS][1] = new PinSetting("Pins/Y2/Phase3", Y2_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][Z_AXIS][0] = new PinSetting("Pins/Z/Phase3", Z_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][Z_AXIS][1] = new PinSetting("Pins/Z2/Phase3", Z2_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][A_AXIS][0] = new PinSetting("Pins/A/Phase3", A_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][A_AXIS][1] = new PinSetting("Pins/A2/Phase3", A2_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][B_AXIS][0] = new PinSetting("Pins/B/Phase3", B_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][B_AXIS][1] = new PinSetting("Pins/B2/Phase3", B2_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][C_AXIS][0] = new PinSetting("Pins/C/Phase3", C_PIN_PHASE_3_DEFAULT);
|
||||
PhasePins[3][C_AXIS][1] = new PinSetting("Pins/C2/Phase3", C2_PIN_PHASE_3_DEFAULT);
|
||||
}
|
@@ -516,9 +516,9 @@ void report_execute_startup_message(const char* line, Error status_code, uint8_t
|
||||
// Prints build info line
|
||||
void report_build_info(const char* line, uint8_t client) {
|
||||
grbl_sendf(client, "[VER:%s.%s:%s]\r\n[OPT:", GRBL_VERSION, GRBL_VERSION_BUILD, line);
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
grbl_send(client, "M"); // TODO Need to deal with M8...it could be disabled
|
||||
#endif
|
||||
if (CoolantMistPin->get() != Pin::UNDEFINED) {
|
||||
grbl_send(client, "M"); // TODO Need to deal with M8...it could be disabled
|
||||
}
|
||||
#ifdef COREXY
|
||||
grbl_send(client, "C");
|
||||
#endif
|
||||
@@ -823,11 +823,12 @@ void report_realtime_status(uint8_t client) {
|
||||
if (coolant.Flood) {
|
||||
strcat(status, "F");
|
||||
}
|
||||
# ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
|
||||
if (coolant.Mist) {
|
||||
strcat(status, "M");
|
||||
if (CoolantMistPin->get() != Pin::UNDEFINED) {
|
||||
// TODO Deal with M8 - Flood
|
||||
if (coolant.Mist) {
|
||||
strcat(status, "M");
|
||||
}
|
||||
}
|
||||
# endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
@@ -941,7 +942,7 @@ char* reportAxisNameMsg(uint8_t axis) {
|
||||
|
||||
void reportTaskStackSize(UBaseType_t& saved) {
|
||||
#ifdef DEBUG_REPORT_STACK_FREE
|
||||
UBaseType_t newHighWater = uxTaskGetStackHighWaterMark(NULL);
|
||||
UBaseType_t newHighWater = uxTaskGetStackHighWaterMark(NULL);
|
||||
if (newHighWater != saved) {
|
||||
saved = newHighWater;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s Min Stack Space: %d", pcTaskGetTaskName(NULL), saved);
|
||||
|
@@ -20,7 +20,9 @@
|
||||
#include <SD.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#define SDCARD_DET_PIN -1
|
||||
#ifndef SDCARD_DET_PIN
|
||||
# define SDCARD_DET_PIN -1
|
||||
#endif
|
||||
const int SDCARD_DET_VAL = 0;
|
||||
|
||||
const int SDCARD_IDLE = 0;
|
||||
@@ -29,8 +31,8 @@ const int SDCARD_BUSY_PRINTING = 2;
|
||||
const int SDCARD_BUSY_UPLOADING = 4;
|
||||
const int SDCARD_BUSY_PARSING = 8;
|
||||
|
||||
extern bool SD_ready_next; // Grbl has processed a line and is waiting for another
|
||||
extern uint8_t SD_client;
|
||||
extern bool SD_ready_next; // Grbl has processed a line and is waiting for another
|
||||
extern uint8_t SD_client;
|
||||
extern WebUI::AuthenticationLevel SD_auth_level;
|
||||
|
||||
//bool sd_mount();
|
||||
|
@@ -35,19 +35,19 @@ IntSetting* status_mask;
|
||||
FloatSetting* junction_deviation;
|
||||
FloatSetting* arc_tolerance;
|
||||
|
||||
FloatSetting* homing_feed_rate;
|
||||
FloatSetting* homing_seek_rate;
|
||||
FloatSetting* homing_debounce;
|
||||
FloatSetting* homing_pulloff;
|
||||
FloatSetting* homing_feed_rate;
|
||||
FloatSetting* homing_seek_rate;
|
||||
FloatSetting* homing_debounce;
|
||||
FloatSetting* homing_pulloff;
|
||||
AxisMaskSetting* homing_cycle[MAX_N_AXIS];
|
||||
FloatSetting* spindle_pwm_freq;
|
||||
FloatSetting* rpm_max;
|
||||
FloatSetting* rpm_min;
|
||||
FloatSetting* spindle_delay_spinup;
|
||||
FloatSetting* spindle_delay_spindown;
|
||||
FlagSetting* spindle_enbl_off_with_zero_speed;
|
||||
FlagSetting* spindle_enable_invert;
|
||||
FlagSetting* spindle_output_invert;
|
||||
FloatSetting* spindle_pwm_freq;
|
||||
FloatSetting* rpm_max;
|
||||
FloatSetting* rpm_min;
|
||||
FloatSetting* spindle_delay_spinup;
|
||||
FloatSetting* spindle_delay_spindown;
|
||||
FlagSetting* spindle_enbl_off_with_zero_speed;
|
||||
FlagSetting* spindle_enable_invert;
|
||||
FlagSetting* spindle_output_invert;
|
||||
|
||||
FloatSetting* spindle_pwm_off_value;
|
||||
FloatSetting* spindle_pwm_min_value;
|
||||
@@ -207,8 +207,8 @@ static const char* makeGrblName(int axisNum, int base) {
|
||||
|
||||
void make_coordinate(CoordIndex index, const char* name) {
|
||||
float coord_data[MAX_N_AXIS] = { 0.0 };
|
||||
auto coord = new Coordinates(name);
|
||||
coords[index] = coord;
|
||||
auto coord = new Coordinates(name);
|
||||
coords[index] = coord;
|
||||
if (!coord->load()) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Propagating %s data to NVS format", coord->getName());
|
||||
// If coord->load() returns false it means that no entry
|
||||
@@ -223,6 +223,9 @@ void make_coordinate(CoordIndex index, const char* name) {
|
||||
coords[index]->set(coord_data);
|
||||
}
|
||||
}
|
||||
|
||||
extern void make_pin_settings();
|
||||
|
||||
void make_settings() {
|
||||
Setting::init();
|
||||
|
||||
@@ -382,4 +385,6 @@ void make_settings() {
|
||||
homing_cycle[3] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle3", DEFAULT_HOMING_CYCLE_3);
|
||||
homing_cycle[4] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle4", DEFAULT_HOMING_CYCLE_4);
|
||||
homing_cycle[5] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle5", DEFAULT_HOMING_CYCLE_5);
|
||||
|
||||
make_pin_settings(); // Created in PinSettingsDefinitions.cpp
|
||||
}
|
||||
|
@@ -66,10 +66,7 @@ extern PinSetting* CoolantMistPin; // COOLANT_MIST_PIN
|
||||
extern PinSetting* ProbePin; // PROBE_PIN
|
||||
extern PinSetting* SDCardDetPin; // SDCARD_DET_PIN
|
||||
extern PinSetting* SteppersDisablePin; // STEPPERS_DISABLE_PIN
|
||||
|
||||
// { { X_LIMIT_PIN, X2_LIMIT_PIN }, { Y_LIMIT_PIN, Y2_LIMIT_PIN }, { Z_LIMIT_PIN, Z2_LIMIT_PIN },
|
||||
// { A_LIMIT_PIN, A2_LIMIT_PIN }, { B_LIMIT_PIN, B2_LIMIT_PIN }, { C_LIMIT_PIN, C2_LIMIT_PIN } };
|
||||
extern PinSetting* limit_pins[MAX_N_AXIS][2];
|
||||
extern PinSetting* StepperResetPin; // STEPPER_RESET
|
||||
|
||||
extern PinSetting* ControlSafetyDoorPin; // CONTROL_SAFETY_DOOR_PIN
|
||||
extern PinSetting* ControlResetPin; // CONTROL_RESET_PIN
|
||||
@@ -79,3 +76,20 @@ extern PinSetting* MacroButton0Pin; // MACRO_BUTTON_0_PIN
|
||||
extern PinSetting* MacroButton1Pin; // MACRO_BUTTON_1_PIN
|
||||
extern PinSetting* MacroButton2Pin; // MACRO_BUTTON_2_PIN
|
||||
extern PinSetting* MacroButton3Pin; // MACRO_BUTTON_3_PIN
|
||||
|
||||
extern PinSetting* DynamixelTXDPin; // DYNAMIXEL_TXD
|
||||
extern PinSetting* DynamixelRXDPin; // DYNAMIXEL_RXD
|
||||
extern PinSetting* DynamixelRTSPin; // DYNAMIXEL_RTS
|
||||
|
||||
extern PinSetting* UserDigitalPin[4];
|
||||
extern PinSetting* UserAnalogPin[4];
|
||||
|
||||
// TODO FIXME: Add motor type (enum) setting! That way we can properly hide a lot of settings, and make Motors.cpp proper!
|
||||
extern PinSetting* LimitPins[MAX_N_AXIS][2];
|
||||
extern PinSetting* StepPins[MAX_N_AXIS][2];
|
||||
extern PinSetting* DirectionPins[MAX_N_AXIS][2];
|
||||
extern PinSetting* DisablePins[MAX_N_AXIS][2];
|
||||
extern PinSetting* ClearToSendPins[MAX_N_AXIS][2];
|
||||
extern PinSetting* ServoPins[MAX_N_AXIS][2];
|
||||
extern PinSetting* PhasePins[4][MAX_N_AXIS][2];
|
||||
extern PinSetting* StepStickMS3[MAX_N_AXIS][2];
|
||||
|
@@ -48,8 +48,10 @@ namespace Spindles {
|
||||
return; // We cannot continue without the output pin
|
||||
}
|
||||
|
||||
auto outputPin = _output_pin.getNative(Pin::Capabilities::PWM);
|
||||
|
||||
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||
ledcAttachPin(_output_pin, _pwm_chan_num); // attach the PWM to the pin
|
||||
ledcAttachPin(outputPin, _pwm_chan_num); // attach the PWM to the pin
|
||||
|
||||
_enable_pin.setAttr(Pin::Attr::Output);
|
||||
_direction_pin.setAttr(Pin::Attr::Output);
|
||||
|
@@ -68,8 +68,10 @@ namespace Spindles {
|
||||
_pwm_min_value = _pwm_off_value;
|
||||
_pwm_max_value = BESC_MAX_PULSE_CNT;
|
||||
|
||||
auto outputPin = _output_pin.getNative(Pin::Capabilities::PWM);
|
||||
|
||||
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||
ledcAttachPin(_output_pin, _pwm_chan_num); // attach the PWM to the pin
|
||||
ledcAttachPin(outputPin, _pwm_chan_num); // attach the PWM to the pin
|
||||
|
||||
_enable_pin.setAttr(Pin::Attr::Output);
|
||||
|
||||
|
@@ -40,7 +40,7 @@ namespace Spindles {
|
||||
|
||||
if (!_output_pin.capabilities().has(Pin::Capabilities::DAC)) { // DAC can only be used on these pins
|
||||
_gpio_ok = false;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "DAC spindle pin invalid %s (pin 25 or 26 only)", _output_pin.name.c_str());
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "DAC spindle pin invalid %s (pin 25 or 26 only)", _output_pin.name().c_str());
|
||||
return;
|
||||
}
|
||||
|
||||
|
@@ -100,16 +100,15 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
|
||||
#endif
|
||||
|
||||
// Setup M62,M63,M64,M65 pins
|
||||
myDigitalOutputs[0] = new UserOutput::DigitalOutput(0, USER_DIGITAL_PIN_0);
|
||||
myDigitalOutputs[1] = new UserOutput::DigitalOutput(1, USER_DIGITAL_PIN_1);
|
||||
myDigitalOutputs[2] = new UserOutput::DigitalOutput(2, USER_DIGITAL_PIN_2);
|
||||
myDigitalOutputs[3] = new UserOutput::DigitalOutput(3, USER_DIGITAL_PIN_3);
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
myDigitalOutputs[i] = new UserOutput::DigitalOutput(i, UserDigitalPin[i]->get());
|
||||
}
|
||||
|
||||
// Setup M67 Pins
|
||||
myAnalogOutputs[0] = new UserOutput::AnalogOutput(0, USER_ANALOG_PIN_0, USER_ANALOG_PIN_0_FREQ);
|
||||
myAnalogOutputs[1] = new UserOutput::AnalogOutput(1, USER_ANALOG_PIN_1, USER_ANALOG_PIN_1_FREQ);
|
||||
myAnalogOutputs[2] = new UserOutput::AnalogOutput(2, USER_ANALOG_PIN_2, USER_ANALOG_PIN_2_FREQ);
|
||||
myAnalogOutputs[3] = new UserOutput::AnalogOutput(3, USER_ANALOG_PIN_3, USER_ANALOG_PIN_3_FREQ);
|
||||
myAnalogOutputs[0] = new UserOutput::AnalogOutput(0, UserAnalogPin[0]->get(), USER_ANALOG_PIN_0_FREQ);
|
||||
myAnalogOutputs[1] = new UserOutput::AnalogOutput(1, UserAnalogPin[1]->get(), USER_ANALOG_PIN_1_FREQ);
|
||||
myAnalogOutputs[2] = new UserOutput::AnalogOutput(2, UserAnalogPin[2]->get(), USER_ANALOG_PIN_2_FREQ);
|
||||
myAnalogOutputs[3] = new UserOutput::AnalogOutput(3, UserAnalogPin[3]->get(), USER_ANALOG_PIN_3_FREQ);
|
||||
}
|
||||
|
||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
@@ -211,12 +210,12 @@ ControlPins system_control_get_state() {
|
||||
}
|
||||
|
||||
defined_pins.bit.feedHold = ControlFeedHoldPin->get() != Pin::UNDEFINED;
|
||||
if (digitalRead(CONTROL_FEED_HOLD_PIN)) {
|
||||
if (ControlFeedHoldPin->get().read()) {
|
||||
pin_states.bit.feedHold = true;
|
||||
}
|
||||
|
||||
defined_pins.bit.cycleStart = ControlCycleStartPin->get() != Pin::UNDEFINED;
|
||||
if (digitalRead(CONTROL_CYCLE_START_PIN)) {
|
||||
if (ControlCycleStartPin->get().read()) {
|
||||
pin_states.bit.cycleStart = true;
|
||||
}
|
||||
|
||||
|
Reference in New Issue
Block a user