diff --git a/Grbl_Esp32/Machines/external_driver_4x.h b/Grbl_Esp32/Machines/4axis_external_driver.h
similarity index 96%
rename from Grbl_Esp32/Machines/external_driver_4x.h
rename to Grbl_Esp32/Machines/4axis_external_driver.h
index 5c6788a9..f88204ad 100644
--- a/Grbl_Esp32/Machines/external_driver_4x.h
+++ b/Grbl_Esp32/Machines/4axis_external_driver.h
@@ -22,7 +22,7 @@
along with Grbl_ESP32. If not, see .
*/
-#define MACHINE_NAME "External Driver Board V1.1"
+#define MACHINE_NAME "External 4 Axis Driver Board"
#ifdef N_AXIS
#undef N_AXIS
diff --git a/Grbl_Esp32/Machines/lowrider.h b/Grbl_Esp32/Machines/lowrider_v1p2.h
similarity index 59%
rename from Grbl_Esp32/Machines/lowrider.h
rename to Grbl_Esp32/Machines/lowrider_v1p2.h
index 5ac71165..67944058 100644
--- a/Grbl_Esp32/Machines/lowrider.h
+++ b/Grbl_Esp32/Machines/lowrider_v1p2.h
@@ -2,7 +2,7 @@
lowrider.h
Part of Grbl_ESP32
- Pin assignments for the Buildlog.net MPCNC controller
+ Pin assignments for the Buildlog.net MPCNC controller
used in lowrider mode. Low rider has (2) Y and Z and one X motor
These will not match the silkscreen or schematic descriptions...see definitions below
https://github.com/bdring/Grbl_ESP32_MPCNC_Controller
@@ -24,28 +24,23 @@
along with Grbl_ESP32. If not, see .
*/
-//#define V1P1
-#define V1P2 // works for V1.2.1 as well
-#ifdef V1P1
-#define MACHINE_NAME "MACHINE_LOWRIDER_V1P1"
-#else // V1P2
+
#define MACHINE_NAME "MACHINE_LOWRIDER_V1P2"
-#endif
#define USE_GANGED_AXES // allow two motors on an axis
-#define X_STEP_PIN GPIO_NUM_27 // use Z labeled connector
-#define X_DIRECTION_PIN GPIO_NUM_33 // use Z labeled connector
+#define X_STEP_PIN GPIO_NUM_27 // use Z labeled connector
+#define X_DIRECTION_PIN GPIO_NUM_33 // use Z labeled connector
-#define Y_STEP_PIN GPIO_NUM_14
-#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
-#define Y_DIRECTION_PIN GPIO_NUM_25
+#define Y_STEP_PIN GPIO_NUM_14
+#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
+#define Y_DIRECTION_PIN GPIO_NUM_25
#define Y_AXIS_SQUARING
-#define Z_STEP_PIN GPIO_NUM_12 // use X labeled connector
-#define Z2_STEP_PIN GPIO_NUM_22 // use X labeled connector
-#define Z_DIRECTION_PIN GPIO_NUM_26 // use X labeled connector
+#define Z_STEP_PIN GPIO_NUM_12 // use X labeled connector
+#define Z2_STEP_PIN GPIO_NUM_22 // use X labeled connector
+#define Z_DIRECTION_PIN GPIO_NUM_26 // use X labeled connector
#define Z_AXIS_SQUARING
// OK to comment out to use pin for other features
@@ -55,40 +50,30 @@
//#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
- #ifdef V1P1
- #define SPINDLE_PWM_PIN GPIO_NUM_17
- #else // V1p2
- #define SPINDLE_PWM_PIN GPIO_NUM_2
- #endif
+ #define SPINDLE_PWM_PIN GPIO_NUM_2
#else
- #define SPINDLE_PWM_PIN GPIO_NUM_16
- #define SPINDLE_ENABLE_PIN GPIO_NUM_32
+ #define SPINDLE_PWM_PIN GPIO_NUM_16
+ #define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
// Relay can be used for Spindle or Coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_17
-#define X_LIMIT_PIN GPIO_NUM_15
-#define Y_LIMIT_PIN GPIO_NUM_4
-
-#ifdef V1P1 //v1p1
- #define Z_LIMIT_PIN GPIO_NUM_2
-#else
- #define Z_LIMIT_PIN GPIO_NUM_17
-#endif
+#define X_LIMIT_PIN GPIO_NUM_15
+#define Y_LIMIT_PIN GPIO_NUM_4
+#define Z_LIMIT_PIN GPIO_NUM_17
#define LIMIT_MASK B111
-#ifdef V1P2
- #ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
- #define ENABLE_SOFTWARE_DEBOUNCE
- #endif
+#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
+ #define ENABLE_SOFTWARE_DEBOUNCE
#endif
+
// The default value in config.h is wrong for this controller
#ifdef INVERT_CONTROL_PIN_MASK
- #undef INVERT_CONTROL_PIN_MASK
+ #undef INVERT_CONTROL_PIN_MASK
#endif
#define INVERT_CONTROL_PIN_MASK B1110
diff --git a/Grbl_Esp32/Machines/mpcnc_v1p1.h b/Grbl_Esp32/Machines/mpcnc_v1p1.h
new file mode 100644
index 00000000..d6c30bd2
--- /dev/null
+++ b/Grbl_Esp32/Machines/mpcnc_v1p1.h
@@ -0,0 +1,141 @@
+/*
+ mpcnc.h
+ Part of Grbl_ESP32
+
+ Pin assignments for the Buildlog.net MPCNC controller
+ https://github.com/bdring/Grbl_ESP32_MPCNC_Controller
+
+ 2019 - Bart Dring
+ 2020 - Mitch Bradley
+
+ Grbl_ESP32 is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ Grbl is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with Grbl_ESP32. If not, see .
+*/
+
+// // Pin assignments for the Buildlog.net MPCNC controller
+
+
+#define MACHINE_NAME "MACHINE_MPCNC_V1P1"
+
+#define USE_GANGED_AXES // allow two motors on an axis
+
+#define X_STEP_PIN GPIO_NUM_12
+#define X2_STEP_PIN GPIO_NUM_22 // ganged motor
+#define X_AXIS_SQUARING
+
+#define Y_STEP_PIN GPIO_NUM_14
+#define Y2_STEP_PIN GPIO_NUM_21 // ganged motor
+#define Y_AXIS_SQUARING
+
+#define Z_STEP_PIN GPIO_NUM_27
+
+#define X_DIRECTION_PIN GPIO_NUM_26
+#define Y_DIRECTION_PIN GPIO_NUM_25
+#define Z_DIRECTION_PIN GPIO_NUM_33
+
+// OK to comment out to use pin for other features
+#define STEPPERS_DISABLE_PIN GPIO_NUM_13
+
+// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
+//#define USE_SPINDLE_RELAY
+
+#ifdef USE_SPINDLE_RELAY
+ #define SPINDLE_PWM_PIN GPIO_NUM_17
+#else
+ #define SPINDLE_PWM_PIN GPIO_NUM_16
+ #define SPINDLE_ENABLE_PIN GPIO_NUM_32
+#endif
+
+// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
+// Relay can be used for spindle or either coolant
+//#define COOLANT_FLOOD_PIN GPIO_NUM_2
+//#define COOLANT_MIST_PIN GPIO_NUM_2
+
+
+#define X_LIMIT_PIN GPIO_NUM_2
+#define Y_LIMIT_PIN GPIO_NUM_4
+#define Z_LIMIT_PIN GPIO_NUM_15
+#define LIMIT_MASK B111
+
+#define PROBE_PIN GPIO_NUM_35
+
+// The default value in config.h is wrong for this controller
+#ifdef INVERT_CONTROL_PIN_MASK
+ #undef INVERT_CONTROL_PIN_MASK
+#endif
+
+#define INVERT_CONTROL_PIN_MASK B1110
+
+// Note: default is #define IGNORE_CONTROL_PINS in config.h
+// uncomment to these lines to use them
+
+/*
+#ifdef IGNORE_CONTROL_PINS
+#undef IGNORE_CONTROL_PINS
+#endif
+*/
+
+#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
+#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
+#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
+
+#define DEFAULT_STEP_PULSE_MICROSECONDS 3
+#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
+
+#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
+#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
+#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
+#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
+#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
+
+#define DEFAULT_STATUS_REPORT_MASK 1
+
+#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
+#define DEFAULT_ARC_TOLERANCE 0.002 // mm
+#define DEFAULT_REPORT_INCHES 0 // false
+
+#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
+#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
+
+#define DEFAULT_HOMING_ENABLE 1 // false
+#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
+#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
+#define DEFAULT_HOMING_SEEK_RATE 200.0 // mm/min
+#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
+#define DEFAULT_HOMING_PULLOFF 2.0 // mm
+
+#ifdef USE_SPINDLE_RELAY
+ #define DEFAULT_SPINDLE_RPM_MAX 1.0 // must be 1 so PWM duty is alway 100% to prevent relay damage
+#else
+ #define DEFAULT_SPINDLE_RPM_MAX 1000.0 // can be change to your spindle max
+#endif
+
+#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
+
+#define DEFAULT_LASER_MODE 0 // false
+
+#define DEFAULT_X_STEPS_PER_MM 200.0
+#define DEFAULT_Y_STEPS_PER_MM 200.0
+#define DEFAULT_Z_STEPS_PER_MM 800.0
+
+#define DEFAULT_X_MAX_RATE 8000.0 // mm/min
+#define DEFAULT_Y_MAX_RATE 8000.0 // mm/min
+#define DEFAULT_Z_MAX_RATE 3000.0 // mm/min
+
+#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
+#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
+#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
+
+#define DEFAULT_X_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
+#define DEFAULT_Y_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
+#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
diff --git a/Grbl_Esp32/Machines/mpcnc.h b/Grbl_Esp32/Machines/mpcnc_v1p2.h
similarity index 64%
rename from Grbl_Esp32/Machines/mpcnc.h
rename to Grbl_Esp32/Machines/mpcnc_v1p2.h
index b9d4bb2a..1ca36502 100644
--- a/Grbl_Esp32/Machines/mpcnc.h
+++ b/Grbl_Esp32/Machines/mpcnc_v1p2.h
@@ -2,7 +2,7 @@
mpcnc.h
Part of Grbl_ESP32
- Pin assignments for the Buildlog.net MPCNC controller
+ Pin assignments for the Buildlog.net MPCNC controller
https://github.com/bdring/Grbl_ESP32_MPCNC_Controller
2019 - Bart Dring
@@ -21,18 +21,12 @@
You should have received a copy of the GNU General Public License
along with Grbl_ESP32. If not, see .
*/
-
+
// // Pin assignments for the Buildlog.net MPCNC controller
-// uncomment ONE of the following versions
-//#define V1P1
-#define V1P2 // works for V1.2.1 as well
-#ifdef V1P1
-#define MACHINE_NAME "MACHINE_MPCNC_V1P1"
-#else // V1P2
+
#define MACHINE_NAME "MACHINE_MPCNC_V1P2"
-#endif
#define USE_GANGED_AXES // allow two motors on an axis
@@ -57,14 +51,10 @@
//#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
-#ifdef V1P1
-#define SPINDLE_PWM_PIN GPIO_NUM_17
-#else // V1p2
-#define SPINDLE_PWM_PIN GPIO_NUM_2
-#endif
+ #define SPINDLE_PWM_PIN GPIO_NUM_2
#else
-#define SPINDLE_PWM_PIN GPIO_NUM_16
-#define SPINDLE_ENABLE_PIN GPIO_NUM_32
+ #define SPINDLE_PWM_PIN GPIO_NUM_16
+ #define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
@@ -72,27 +62,23 @@
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
//#define COOLANT_MIST_PIN GPIO_NUM_2
-#ifdef V1P1 //v1p1
-#define X_LIMIT_PIN GPIO_NUM_2
-#else
-#define X_LIMIT_PIN GPIO_NUM_17
-#endif
+#define X_LIMIT_PIN GPIO_NUM_17
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
-#ifdef V1P2
+
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
-#define ENABLE_SOFTWARE_DEBOUNCE
-#endif
+ #define ENABLE_SOFTWARE_DEBOUNCE
#endif
+
#define PROBE_PIN GPIO_NUM_35
// The default value in config.h is wrong for this controller
#ifdef INVERT_CONTROL_PIN_MASK
-#undef INVERT_CONTROL_PIN_MASK
+ #undef INVERT_CONTROL_PIN_MASK
#endif
#define INVERT_CONTROL_PIN_MASK B1110
@@ -106,39 +92,39 @@
#endif
*/
-#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
-#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
-#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
+#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
+#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
+#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
-#define DEFAULT_STEP_PULSE_MICROSECONDS 3
-#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
+#define DEFAULT_STEP_PULSE_MICROSECONDS 3
+#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
-#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
-#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
-#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
-#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
-#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
+#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
+#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
+#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
+#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
+#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
-#define DEFAULT_STATUS_REPORT_MASK 1
+#define DEFAULT_STATUS_REPORT_MASK 1
-#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
-#define DEFAULT_ARC_TOLERANCE 0.002 // mm
-#define DEFAULT_REPORT_INCHES 0 // false
+#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
+#define DEFAULT_ARC_TOLERANCE 0.002 // mm
+#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
-#define DEFAULT_HOMING_ENABLE 1 // false
-#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
-#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
-#define DEFAULT_HOMING_SEEK_RATE 200.0 // mm/min
-#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
-#define DEFAULT_HOMING_PULLOFF 2.0 // mm
+#define DEFAULT_HOMING_ENABLE 1 // false
+#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
+#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
+#define DEFAULT_HOMING_SEEK_RATE 200.0 // mm/min
+#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
+#define DEFAULT_HOMING_PULLOFF 2.0 // mm
#ifdef USE_SPINDLE_RELAY
-#define DEFAULT_SPINDLE_RPM_MAX 1.0 // must be 1 so PWM duty is alway 100% to prevent relay damage
+ #define DEFAULT_SPINDLE_RPM_MAX 1.0 // must be 1 so PWM duty is alway 100% to prevent relay damage
#else
-#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // can be change to your spindle max
+ #define DEFAULT_SPINDLE_RPM_MAX 1000.0 // can be change to your spindle max
#endif
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm