diff --git a/Grbl_Esp32/Custom/CoreXY.cpp b/Grbl_Esp32/Custom/CoreXY.cpp
index cefab842..39488722 100644
--- a/Grbl_Esp32/Custom/CoreXY.cpp
+++ b/Grbl_Esp32/Custom/CoreXY.cpp
@@ -43,7 +43,6 @@ const float geometry_factor = 1.0;
const float geometry_factor = 2.0;
#endif
-static float last_motors[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
static float last_cartesian[MAX_N_AXIS] = {};
// prototypes for helper functions
@@ -51,9 +50,28 @@ float three_axis_dist(float* point1, float* point2);
void machine_init() {
// print a startup message to show the kinematics are enable
+
+#ifdef MIDTBOT
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY (midTbot) Kinematics Init");
+#else
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY Kinematics Init");
+#endif
}
+// Converts Cartesian to motors with no motion control
+static void cartesian_to_motors(float* position) {
+ float motors[MAX_N_AXIS];
+
+ motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
+ motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];
+
+ position[X_AXIS] = motors[X_AXIS];
+ position[Y_AXIS] = motors[Y_AXIS];
+
+ // Z and higher just pass through unchanged
+}
+
+// Cycle mask is 0 unless the user sends a single axis command like $HZ
// This will always return true to prevent the normal Grbl homing cycle
bool user_defined_homing(uint8_t cycle_mask) {
uint8_t n_cycle; // each home is a multi cycle operation approach, pulloff, approach.....
@@ -61,15 +79,10 @@ bool user_defined_homing(uint8_t cycle_mask) {
float max_travel;
uint8_t axis;
- // check for single axis homing
- if (cycle_mask != 0) {
- grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "CoreXY Single axis homing not allowed. Use $H only");
- return true;
- }
-
// check for multi axis homing per cycle ($Homing/Cycle0=XY type)...not allowed in CoreXY
bool setting_error = false;
- for (int cycle = 0; cycle < 3; cycle++) {
+ auto n_axis = number_axis->get();
+ for (int cycle = 0; cycle < n_axis; cycle++) {
if (numberOfSetBits(homing_cycle[cycle]->get()) > 1) {
grbl_msg_sendf(CLIENT_SERIAL,
MsgLevel::Info,
@@ -90,10 +103,22 @@ bool user_defined_homing(uint8_t cycle_mask) {
pl_data->motion.systemMotion = 1;
pl_data->motion.noFeedOverride = 1;
- for (int cycle = 0; cycle < 3; cycle++) {
- AxisMask mask = homing_cycle[cycle]->get();
+ uint8_t cycle_count = (cycle_mask == 0) ? n_axis : 1; // if we have a cycle_mask, we are only going to do one axis
+
+ AxisMask mask = 0;
+ for (int cycle = 0; cycle < cycle_count; cycle++) {
+ // if we have a cycle_mask, do that. Otherwise get the cycle from the settings
+ mask = cycle_mask ? cycle_mask : homing_cycle[cycle]->get();
+
+ // If not X or Y do a normal home
+ if (!(bitnum_istrue(mask, X_AXIS) || bitnum_istrue(mask, Y_AXIS))) {
+ limits_go_home(mask); // Homing cycle 0
+ continue; // continue to next item in for loop
+ }
+
mask = motors_set_homing_mode(mask, true); // non standard homing motors will do their own thing and get removed from the mask
- for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) {
+
+ for (uint8_t axis = X_AXIS; axis <= n_axis; axis++) {
if (bit(axis) == mask) {
// setup for the homing of this axis
bool approach = true;
@@ -117,10 +142,12 @@ bool user_defined_homing(uint8_t cycle_mask) {
approach ? target[axis] = max_travel : target[axis] = -max_travel;
}
- target[Z_AXIS] = system_convert_axis_steps_to_mpos(sys_position, Z_AXIS);
+ for (int axis = Z_AXIS; axis < n_axis; axis++) {
+ target[axis] = sys_position[axis] / axis_settings[axis]->steps_per_mm->get();
+ }
// convert back to motor steps
- inverse_kinematics(target);
+ cartesian_to_motors(target);
pl_data->feed_rate = homing_rate; // feed or seek rates
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
@@ -190,7 +217,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
} while (n_cycle-- > 0);
}
}
- }
+ } // for
// after sussefully setting X & Y axes, we set the current positions
@@ -205,10 +232,13 @@ bool user_defined_homing(uint8_t cycle_mask) {
last_cartesian[X_AXIS] = target[X_AXIS];
last_cartesian[Y_AXIS] = target[Y_AXIS];
- last_cartesian[Z_AXIS] = system_convert_axis_steps_to_mpos(sys_position, Z_AXIS);
+
+ for (int axis = Z_AXIS; axis < n_axis; axis++) {
+ last_cartesian[axis] = sys_position[axis] / axis_settings[axis]->steps_per_mm->get();
+ }
// convert to motors
- inverse_kinematics(target);
+ cartesian_to_motors(target);
// convert to steps
for (axis = X_AXIS; axis <= Y_AXIS; axis++) {
sys_position[axis] = target[axis] * axis_settings[axis]->steps_per_mm->get();
@@ -224,29 +254,21 @@ bool user_defined_homing(uint8_t cycle_mask) {
return true;
}
-// This function is used by Grbl convert Cartesian to motors
-// this does not do any motion control
-void inverse_kinematics(float* position) {
- float motors[3];
+static void transform_cartesian_to_motors(float* motors, float* cartesian) {
+ motors[X_AXIS] = geometry_factor * cartesian[X_AXIS] + cartesian[Y_AXIS];
+ motors[Y_AXIS] = geometry_factor * cartesian[X_AXIS] - cartesian[Y_AXIS];
- motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
- motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];
- motors[Z_AXIS] = position[Z_AXIS];
-
- position[0] = motors[0];
- position[1] = motors[1];
- position[2] = motors[2];
+ auto n_axis = number_axis->get();
+ for (uint8_t axis = Z_AXIS; axis <= n_axis; axis++) {
+ motors[axis] = cartesian[axis];
+ }
}
// Inverse Kinematics calculates motor positions from real world cartesian positions
-// position is the current position
+// position is the old machine position, target the new machine position
// Breaking into segments is not needed with CoreXY, because it is a linear system.
-void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
-{
+bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
float dx, dy, dz; // distances in each cartesian axis
- float motors[MAX_N_AXIS];
-
- float feed_rate = pl_data->feed_rate; // save original feed rate
// calculate cartesian move distance for each axis
dx = target[X_AXIS] - position[X_AXIS];
@@ -254,31 +276,31 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
dz = target[Z_AXIS] - position[Z_AXIS];
float dist = sqrt((dx * dx) + (dy * dy) + (dz * dz));
- motors[X_AXIS] = geometry_factor * target[X_AXIS] + target[Y_AXIS];
- motors[Y_AXIS] = geometry_factor * target[X_AXIS] - target[Y_AXIS];
- motors[Z_AXIS] = target[Z_AXIS];
+ auto n_axis = number_axis->get();
- float motor_distance = three_axis_dist(motors, last_motors);
+ float motors[n_axis];
+ transform_cartesian_to_motors(motors, target);
if (!pl_data->motion.rapidMotion) {
- pl_data->feed_rate *= (motor_distance / dist);
+ float last_motors[n_axis];
+ transform_cartesian_to_motors(last_motors, position);
+ pl_data->feed_rate *= (three_axis_dist(motors, last_motors) / dist);
}
- memcpy(last_motors, motors, sizeof(motors));
-
- mc_line(motors, pl_data);
+ return mc_line(motors, pl_data);
}
// motors -> cartesian
-void forward_kinematics(float* position) {
- float calc_fwd[MAX_N_AXIS];
-
+void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
+ // apply the forward kinemetics to the machine coordinates
// https://corexy.com/theory.html
- calc_fwd[X_AXIS] = 0.5 / geometry_factor * (position[X_AXIS] + position[Y_AXIS]);
- calc_fwd[Y_AXIS] = 0.5 * (position[X_AXIS] - position[Y_AXIS]);
+ //calc_fwd[X_AXIS] = 0.5 / geometry_factor * (position[X_AXIS] + position[Y_AXIS]);
+ cartesian[X_AXIS] = 0.5 * (motors[X_AXIS] + motors[Y_AXIS]) / geometry_factor;
+ cartesian[Y_AXIS] = 0.5 * (motors[X_AXIS] - motors[Y_AXIS]);
- position[X_AXIS] = calc_fwd[X_AXIS];
- position[Y_AXIS] = calc_fwd[Y_AXIS];
+ for (int axis = Z_AXIS; axis < n_axis; axis++) {
+ cartesian[axis] = motors[axis];
+ }
}
bool kinematics_pre_homing(uint8_t cycle_mask) {
@@ -286,14 +308,13 @@ bool kinematics_pre_homing(uint8_t cycle_mask) {
}
void kinematics_post_homing() {
- gc_state.position[X_AXIS] = last_cartesian[X_AXIS];
- gc_state.position[Y_AXIS] = last_cartesian[Y_AXIS];
- gc_state.position[Z_AXIS] = last_cartesian[Z_AXIS];
+ auto n_axis = number_axis->get();
+ memcpy(gc_state.position, last_cartesian, n_axis * sizeof(last_cartesian[0]));
}
-// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
-uint8_t kinematic_limits_check(float* target) {
- return true;
+// this is used used by Limits.cpp to see if the range of the machine is exceeded.
+bool limitsCheckTravel(float* target) {
+ return false;
}
void user_m30() {}
diff --git a/Grbl_Esp32/Custom/atari_1020.cpp b/Grbl_Esp32/Custom/atari_1020.cpp
index 01ddaa50..086e28fc 100644
--- a/Grbl_Esp32/Custom/atari_1020.cpp
+++ b/Grbl_Esp32/Custom/atari_1020.cpp
@@ -58,7 +58,8 @@ void machine_init() {
NULL, // parameters
1, // priority
&solenoidSyncTaskHandle,
- 0 // core
+ CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
+ // core
);
// setup a task that will do the custom homing sequence
xTaskCreatePinnedToCore(atari_home_task, // task
@@ -67,22 +68,20 @@ void machine_init() {
NULL, // parameters
1, // priority
&atariHomingTaskHandle,
- 0 // core
+ CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
+ // core
);
}
// this task tracks the Z position and sets the solenoid
void solenoidSyncTask(void* pvParameters) {
int32_t current_position[N_AXIS]; // copy of current location
- float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TASK_FREQ; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) {
// don't ever return from this or the task dies
- memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
- system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
- calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
+ calc_solenoid(system_get_mpos()[Z_AXIS]); // calculate kinematics and move the servos
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
}
}
diff --git a/Grbl_Esp32/Custom/custom_code_template.cpp b/Grbl_Esp32/Custom/custom_code_template.cpp
index bd468f6d..54d5f6ec 100644
--- a/Grbl_Esp32/Custom/custom_code_template.cpp
+++ b/Grbl_Esp32/Custom/custom_code_template.cpp
@@ -24,37 +24,39 @@
=======================================================================
This is a template for user-defined C++ code functions. Grbl can be
-configured to call some optional functions, enabled by #define statements
-in the machine definition .h file. Implement the functions thus enabled
-herein. The possible functions are listed and described below.
+configured to call some optional functions. These functions have weak definitions
+in the main code. If you create your own version they will be used instead
-To use this file, copy it to a name of your own choosing, and also copy
-Machines/template.h to a similar name.
+Put all of your functions in a .cpp file in the "Custom" folder.
+Add this to your machine definition file
+#define CUSTOM_CODE_FILENAME "../Custom/YourFile.cpp"
-Example:
-Machines/my_machine.h
-Custom/my_machine.cpp
-
-Edit machine.h to include your Machines/my_machine.h file
-
-Edit Machines/my_machine.h according to the instructions therein.
-
-Fill in the function definitions below for the functions that you have
-enabled with USE_ defines in Machines/my_machine.h
+Be careful to return the correct values
===============================================================================
+Below are all the current weak function
+
*/
-#ifdef USE_MACHINE_INIT
/*
-machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
-special things your machine needs at startup.
+This function is used as a one time setup for your machine.
*/
void machine_init() {}
-#endif
-#ifdef USE_CUSTOM_HOMING
+/*
+This is used to initialize a display.
+*/
+void display_init() {}
+
+/*
+ limitsCheckTravel() is called to check soft limits
+ It returns true if the motion is outside the limit values
+*/
+bool limitsCheckTravel() {
+ return false;
+}
+
/*
user_defined_homing(uint8_t cycle_mask) is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing(uint8_t cycle_mask) returns false, the rest of normal Grbl_ESP32
@@ -66,17 +68,14 @@ bool user_defined_homing(uint8_t cycle_mask) {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}
-#endif
-#ifdef USE_KINEMATICS
/*
Inverse Kinematics converts X,Y,Z cartesian coordinate to the steps
on your "joint" motors. It requires the following three functions:
*/
/*
- inverse_kinematics() looks at incoming move commands and modifies
- them before Grbl_ESP32 puts them in the motion planner.
+ cartesian_to_motors() converts from cartesian coordinates to motor space.
Grbl_ESP32 processes arcs by converting them into tiny little line segments.
Kinematics in Grbl_ESP32 works the same way. Search for this function across
@@ -86,9 +85,9 @@ bool user_defined_homing(uint8_t cycle_mask) {
pl_data = planner data (see the definition of this type to see what it is)
position = an N_AXIS array of where the machine is starting from for this move
*/
-void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
+bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
// this simply moves to the target. Replace with your kinematics.
- mc_line(target, pl_data);
+ return mc_line(target, pl_data);
}
/*
@@ -97,8 +96,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
cycle_mask is a bit mask of the axes being homed this time.
*/
-bool kinematics_pre_homing(uint8_t cycle_mask))
-{
+bool kinematics_pre_homing(uint8_t cycle_mask) {
return false; // finish normal homing cycle
}
@@ -106,51 +104,34 @@ bool kinematics_pre_homing(uint8_t cycle_mask))
kinematics_post_homing() is called at the end of normal homing
*/
void kinematics_post_homing() {}
-#endif
-#ifdef USE_FWD_KINEMATICS
/*
- The status command uses forward_kinematics() to convert
+ The status command uses motors_to_cartesian() to convert
your motor positions to cartesian X,Y,Z... coordinates.
Convert the N_AXIS array of motor positions to cartesian in your code.
*/
-void forward_kinematics(float* position) {
+void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
// position[X_AXIS] =
// position[Y_AXIS] =
}
-#endif
-#ifdef USE_TOOL_CHANGE
/*
user_tool_change() is called when tool change gcode is received,
to perform appropriate actions for your machine.
*/
void user_tool_change(uint8_t new_tool) {}
-#endif
-#if defined(MACRO_BUTTON_0_PIN) || defined(MACRO_BUTTON_1_PIN) || defined(MACRO_BUTTON_2_PIN)
/*
options. user_defined_macro() is called with the button number to
perform whatever actions you choose.
*/
void user_defined_macro(uint8_t index) {}
-#endif
-#ifdef USE_M30
/*
user_m30() is called when an M30 gcode signals the end of a gcode file.
*/
void user_m30() {}
-#endif
-
-#ifdef USE_MACHINE_TRINAMIC_INIT
-/*
- machine_triaminic_setup() replaces the normal setup of trinamic
- drivers with your own code. For example, you could setup StallGuard
-*/
-void machine_trinamic_setup() {}
-#endif
// If you add any additional functions specific to your machine that
// require calls from common code, guard their calls in the common code with
diff --git a/Grbl_Esp32/Custom/oled_basic.cpp b/Grbl_Esp32/Custom/oled_basic.cpp
new file mode 100644
index 00000000..b1e2862b
--- /dev/null
+++ b/Grbl_Esp32/Custom/oled_basic.cpp
@@ -0,0 +1,283 @@
+/*
+ oled_basic.cpp
+ Part of Grbl_ESP32
+
+ copyright (c) 2018 - Bart Dring This file was modified for use on the ESP32
+ CPU. Do not use this with Grbl for atMega328P
+
+ Grbl 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. If not, see .
+
+ --------------------------------------------------------------
+
+ This is a minimal implentation of a display as a test project.
+ It is designed to be used with a machine that has no easily accessible serial connection
+ It shows basic status and connection information.
+
+ When in alarm mode it will show the current Wifi/BT paramaters and status
+ Most machines will start in alarm mode (needs homing)
+ If the machine is running a job from SD it will show the progress
+ In other modes it will show state and 3 axis DROs
+ Thats All!
+
+ Library Infor:
+ https://github.com/ThingPulse/esp8266-oled-ssd1306
+
+ Install to PlatformIO with this typed at the terminal
+ platformio lib install 562
+
+ Add this to your machine definition file
+ #define DISPLAY_CODE_FILENAME "Custom/oled_basic.cpp"
+*/
+
+// Include the correct display library
+
+#include "SSD1306Wire.h"
+#include "../src/WebUI/WebSettings.h"
+
+#ifndef OLED_ADDRESS
+# define OLED_ADDRESS 0x3c
+#endif
+
+#ifndef OLED_SDA
+# define OLED_SDA GPIO_NUM_14
+#endif
+
+#ifndef OLED_SCL
+# define OLED_SCL GPIO_NUM_13
+#endif
+
+#ifndef OLED_GEOMETRY
+# define OLED_GEOMETRY GEOMETRY_128_64
+#endif
+
+SSD1306Wire display(OLED_ADDRESS, OLED_SDA, OLED_SCL, OLED_GEOMETRY);
+
+static TaskHandle_t displayUpdateTaskHandle = 0;
+
+// This displays the status of the ESP32 Radios...BT, WiFi, etc
+void displayRadioInfo() {
+ String radio_addr = "";
+ String radio_name = "";
+ String radio_status = "";
+
+#ifdef ENABLE_BLUETOOTH
+ if (WebUI::wifi_radio_mode->get() == ESP_BT) {
+ radio_name = String("BT: ") + WebUI::bt_name->get();
+ }
+#endif
+#ifdef ENABLE_WIFI
+ if ((WiFi.getMode() == WIFI_MODE_STA) || (WiFi.getMode() == WIFI_MODE_APSTA)) {
+ radio_name = "STA: " + WiFi.SSID();
+ radio_addr = WiFi.localIP().toString();
+ } else if ((WiFi.getMode() == WIFI_MODE_AP) || (WiFi.getMode() == WIFI_MODE_APSTA)) {
+ radio_name = String("AP:") + WebUI::wifi_ap_ssid->get();
+ radio_addr = WiFi.softAPIP().toString();
+ }
+#endif
+
+#ifdef WIFI_OR_BLUETOOTH
+ if (WebUI::wifi_radio_mode->get() == ESP_RADIO_OFF) {
+ radio_name = "Radio Mode: None";
+ }
+#else
+ radio_name = "Radio Mode:Disabled";
+#endif
+
+ display.setTextAlignment(TEXT_ALIGN_LEFT);
+ display.setFont(ArialMT_Plain_10);
+
+ if (sys.state == State::Alarm) { // print below Alarm:
+ display.drawString(0, 18, radio_name);
+ display.drawString(0, 30, radio_addr);
+
+ } else { // print next to status
+ if (WebUI::wifi_radio_mode->get() == ESP_BT) {
+ display.drawString(55, 2, radio_name);
+ } else {
+ display.drawString(55, 2, radio_addr);
+ }
+ }
+}
+// Here changes begin Here changes begin Here changes begin Here changes begin Here changes begin
+
+void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool checked) {
+ if (checked)
+ display.fillRect(x, y, width, height); // If log.0
+ else
+ display.drawRect(x, y, width, height); // If log.1
+}
+
+void displayDRO() {
+ uint8_t oled_y_pos;
+ //float wco[MAX_N_AXIS];
+
+ display.setTextAlignment(TEXT_ALIGN_LEFT);
+ display.setFont(ArialMT_Plain_10);
+
+ char axisVal[20];
+
+ display.drawString(80, 14, "L"); // Limit switch
+
+ auto n_axis = number_axis->get();
+ AxisMask lim_pin_state = limits_get_state();
+ ControlPins ctrl_pin_state = system_control_get_state();
+ bool prb_pin_state = probe_get_state();
+
+ display.setTextAlignment(TEXT_ALIGN_RIGHT);
+
+ float* print_position = system_get_mpos();
+ if (bit_istrue(status_mask->get(), RtStatus::Position)) {
+ display.drawString(60, 14, "M Pos");
+ } else {
+ display.drawString(60, 14, "W Pos");
+ mpos_to_wpos(print_position);
+ }
+
+ for (uint8_t axis = X_AXIS; axis < n_axis; axis++) {
+ oled_y_pos = 24 + (axis * 10);
+
+ String axis_letter = String(report_get_axis_letter(axis));
+ axis_letter += ":";
+ display.setTextAlignment(TEXT_ALIGN_LEFT);
+ display.drawString(0, oled_y_pos, axis_letter); // String('X') + ":");
+
+ display.setTextAlignment(TEXT_ALIGN_RIGHT);
+ snprintf(axisVal, 20 - 1, "%.3f", print_position[axis]);
+ display.drawString(60, oled_y_pos, axisVal);
+
+ if (limitsSwitchDefined(axis, 0)) { // olny draw the box if a switch has been defined
+ draw_checkbox(80, 27 + (axis * 10), 7, 7, bit_istrue(lim_pin_state, bit(axis)));
+ }
+ }
+
+ oled_y_pos = 14;
+
+ if (PROBE_PIN != UNDEFINED_PIN) {
+ display.drawString(110, oled_y_pos, "P");
+ draw_checkbox(120, oled_y_pos + 3, 7, 7, prb_pin_state);
+ oled_y_pos += 10;
+ }
+
+#ifdef CONTROL_FEED_HOLD_PIN
+ display.drawString(110, oled_y_pos, "H");
+ draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.feedHold);
+ oled_y_pos += 10;
+#endif
+
+#ifdef CONTROL_CYCLE_START_PIN
+ display.drawString(110, oled_y_pos, "S");
+ draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.cycleStart);
+ oled_y_pos += 10;
+#endif
+
+#ifdef CONTROL_RESET_PIN
+ display.drawString(110, oled_y_pos, "R");
+ draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.reset);
+ oled_y_pos += 10;
+#endif
+
+#ifdef CONTROL_SAFETY_DOOR_PIN
+ display.drawString(110, oled_y_pos, "D");
+ draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pin_state.bit.safetyDoor);
+#endif
+}
+
+void displayUpdate(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xDisplayFrequency = 100; // in ticks (typically ms)
+ xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
+
+ vTaskDelay(2500);
+ uint16_t sd_file_ticker = 0;
+
+ display.init();
+ display.flipScreenVertically();
+
+ while (true) {
+ display.clear();
+
+ String state_string = "";
+
+ display.setTextAlignment(TEXT_ALIGN_LEFT);
+ display.setFont(ArialMT_Plain_16);
+ display.drawString(0, 0, report_state_text());
+
+ if (get_sd_state(false) == SDState::BusyPrinting) {
+ display.clear();
+ display.setTextAlignment(TEXT_ALIGN_CENTER);
+ display.setFont(ArialMT_Plain_10);
+ state_string = "SD File";
+ for (int i = 0; i < sd_file_ticker % 10; i++) {
+ state_string += ".";
+ }
+ sd_file_ticker++;
+ display.drawString(63, 0, state_string);
+
+ char path[50];
+ sd_get_current_filename(path);
+ display.drawString(63, 12, path);
+
+ int progress = sd_report_perc_complete();
+ // draw the progress bar
+ display.drawProgressBar(0, 45, 120, 10, progress);
+
+ // draw the percentage as String
+ display.setFont(ArialMT_Plain_10);
+ display.setTextAlignment(TEXT_ALIGN_CENTER);
+ display.drawString(64, 25, String(progress) + "%");
+
+ } else if (sys.state == State::Alarm) {
+ displayRadioInfo();
+ } else {
+ displayDRO();
+ displayRadioInfo();
+ }
+
+ display.display();
+
+ vTaskDelayUntil(&xLastWakeTime, xDisplayFrequency);
+ }
+}
+
+void display_init() {
+ // Initialising the UI will init the display too.
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Init Basic OLED SDA:%s SCL:%s", pinName(OLED_SDA), pinName(OLED_SCL));
+ display.init();
+
+ display.flipScreenVertically();
+
+ display.clear();
+
+ display.setTextAlignment(TEXT_ALIGN_CENTER);
+ display.setFont(ArialMT_Plain_10);
+
+ String mach_name = MACHINE_NAME;
+ // remove characters from the end until the string fits
+ while (display.getStringWidth(mach_name) > 128) {
+ mach_name = mach_name.substring(0, mach_name.length() - 1);
+ }
+ display.drawString(63, 0, mach_name);
+
+ display.display();
+
+ xTaskCreatePinnedToCore(displayUpdate, // task
+ "displayUpdateTask", // name for task
+ 4096, // size of task stack
+ NULL, // parameters
+ 1, // priority
+ &displayUpdateTaskHandle,
+ CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
+ // core
+ );
+}
diff --git a/Grbl_Esp32/Custom/parallel_delta.cpp b/Grbl_Esp32/Custom/parallel_delta.cpp
index a82de59b..23b28a81 100644
--- a/Grbl_Esp32/Custom/parallel_delta.cpp
+++ b/Grbl_Esp32/Custom/parallel_delta.cpp
@@ -91,7 +91,6 @@ static float last_cartesian[N_AXIS] = {
}; // A place to save the previous motor angles for distance/feed rate calcs // Z offset of the effector from the arm centers
// prototypes for helper functions
-int calc_forward_kinematics(float* angles, float* cartesian);
KinematicError delta_calcInverse(float* cartesian, float* angles);
KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta);
float three_axis_dist(float* point1, float* point2);
@@ -108,11 +107,9 @@ void machine_init() {
delta_crank_side_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/CrankSideLength", LENGTH_FIXED_SIDE, 20.0, 500.0);
delta_effector_side_len = new FloatSetting(EXTENDED, WG, NULL, "Delta/EffectorSideLength", LENGTH_EFF_SIDE, 20.0, 500.0);
- read_settings();
-
// Calculate the Z offset at the arm zero angles ...
// Z offset is the z distance from the motor axes to the end effector axes at zero angle
- calc_forward_kinematics(angles, cartesian); // Sets the cartesian values
+ motors_to_cartesian(cartesian, angles, 3); // Sets the cartesian values
// print a startup message to show the kinematics are enabled. Print the offset for reference
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Delta Kinematics Init: %s Z Offset:%4.3f", MACHINE_NAME, cartesian[Z_AXIS]);
@@ -126,32 +123,20 @@ void machine_init() {
// DXL_COUNT_MAX,
// DXL_COUNT_PER_RADIAN);
}
-bool user_defined_homing(uint8_t cycle_mask) { // true = do not continue with normal Grbl homing
-#ifdef USE_CUSTOM_HOMING
- return true;
-#else
- return false;
-#endif
-}
-// This function is used by Grbl
-void inverse_kinematics(float* position) {
- float motor_angles[3];
+// bool user_defined_homing(uint8_t cycle_mask) { // true = do not continue with normal Grbl homing
+// #ifdef USE_CUSTOM_HOMING
+// return true;
+// #else
+// return false;
+// #endif
+// }
- read_settings();
- delta_calcInverse(position, motor_angles);
- position[0] = motor_angles[0];
- position[1] = motor_angles[1];
- position[2] = motor_angles[2];
-}
-
-// This function is used by Grbl
-void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
-{
+bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
float dx, dy, dz; // distances in each cartesian axis
float motor_angles[3];
- float seg_target[3]; // The target of the current segment
+ float seg_target[3]; // The target of the current segment
float feed_rate = pl_data->feed_rate; // save original feed rate
bool show_error = true; // shows error once
@@ -162,16 +147,17 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
// grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Start %3.3f %3.3f %3.3f", position[0], position[1], position[2]);
// grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Target %3.3f %3.3f %3.3f", target[0], target[1], target[2]);
- status = delta_calcInverse(position, motor_angles);
+ status = delta_calcInverse(position, last_angle);
if (status == KinematicError::OUT_OF_RANGE) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Start position error %3.3f %3.3f %3.3f", position[0], position[1], position[2]);
- //start_position_error = true;
+ return false;
}
// Check the destination to see if it is in work area
status = delta_calcInverse(target, motor_angles);
if (status == KinematicError::OUT_OF_RANGE) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Target unreachable error %3.3f %3.3f %3.3f", target[0], target[1], target[2]);
+ return false;
}
position[X_AXIS] += gc_state.coord_offset[X_AXIS];
@@ -198,21 +184,7 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
// calculate the delta motor angles
KinematicError status = delta_calcInverse(seg_target, motor_angles);
- if (status == KinematicError ::NONE) {
- float delta_distance = three_axis_dist(motor_angles, last_angle);
-
- // save angles for next distance calc
- memcpy(last_angle, motor_angles, sizeof(motor_angles));
-
- if (pl_data->motion.rapidMotion) {
- pl_data->feed_rate = feed_rate;
- } else {
- pl_data->feed_rate = (feed_rate * delta_distance / segment_dist);
- }
-
- mc_line(motor_angles, pl_data);
-
- } else {
+ if (status != KinematicError ::NONE) {
if (show_error) {
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
@@ -223,35 +195,52 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
// motor_angles[2]);
show_error = false;
}
+ return false;
}
+ if (pl_data->motion.rapidMotion) {
+ pl_data->feed_rate = feed_rate;
+ } else {
+ float delta_distance = three_axis_dist(motor_angles, last_angle);
+ pl_data->feed_rate = (feed_rate * delta_distance / segment_dist);
+ }
+
+ // mc_line() returns false if a jog is cancelled.
+ // In that case we stop sending segments to the planner.
+ if (!mc_line(motor_angles, pl_data)) {
+ return false;
+ }
+
+ // save angles for next distance calc
+ // This is after mc_line() so that we do not update
+ // last_angle if the segment was discarded.
+ memcpy(last_angle, motor_angles, sizeof(motor_angles));
}
+ return true;
}
// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
-uint8_t kinematic_limits_check(float* target) {
+bool limitsCheckTravel(float* target) {
float motor_angles[3];
read_settings();
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin Soft Check %3.3f, %3.3f, %3.3f", target[0], target[1], target[2]);
- KinematicError status = delta_calcInverse(target, motor_angles);
-
- switch (status) {
+ switch (delta_calcInverse(target, motor_angles)) {
case KinematicError::OUT_OF_RANGE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target out of range");
- break;
+ return true;
case KinematicError::ANGLE_TOO_NEGATIVE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target max negative");
- break;
+ return true;
case KinematicError::ANGLE_TOO_POSITIVE:
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Kin target max positive");
- break;
+ return true;
case KinematicError::NONE:
- break;
+ return false;
}
- return (status == KinematicError::NONE);
+ return false;
}
// inverse kinematics: cartesian -> angles
@@ -286,19 +275,21 @@ KinematicError delta_calcInverse(float* cartesian, float* angles) {
}
// inverse kinematics: angles -> cartesian
-int calc_forward_kinematics(float* angles, float* catesian) {
+void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
+ read_settings();
+
float t = (f - e) * tan30 / 2;
- float y1 = -(t + rf * cos(angles[0]));
- float z1 = -rf * sin(angles[0]);
+ float y1 = -(t + rf * cos(motors[0]));
+ float z1 = -rf * sin(motors[0]);
- float y2 = (t + rf * cos(angles[1])) * sin30;
+ float y2 = (t + rf * cos(motors[1])) * sin30;
float x2 = y2 * tan60;
- float z2 = -rf * sin(angles[1]);
+ float z2 = -rf * sin(motors[1]);
- float y3 = (t + rf * cos(angles[2])) * sin30;
+ float y3 = (t + rf * cos(motors[2])) * sin30;
float x3 = -y3 * tan60;
- float z3 = -rf * sin(angles[2]);
+ float z3 = -rf * sin(motors[2]);
float dnm = (y2 - y1) * x3 - (y3 - y1) * x2;
@@ -321,14 +312,16 @@ int calc_forward_kinematics(float* angles, float* catesian) {
// discriminant
float d = b * b - (float)4.0 * a * c;
- if (d < 0)
- return -1; // non-existing point
+ if (d < 0) {
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "MSG:Fwd Kin Error");
+ return;
+ }
- catesian[Z_AXIS] = -(float)0.5 * (b + sqrt(d)) / a;
- catesian[X_AXIS] = (a1 * catesian[Z_AXIS] + b1) / dnm;
- catesian[Y_AXIS] = (a2 * catesian[Z_AXIS] + b2) / dnm;
- return 0;
+ cartesian[Z_AXIS] = -(float)0.5 * (b + sqrt(d)) / a;
+ cartesian[X_AXIS] = (a1 * cartesian[Z_AXIS] + b1) / dnm;
+ cartesian[Y_AXIS] = (a2 * cartesian[Z_AXIS] + b2) / dnm;
}
+
// helper functions, calculates angle theta1 (for YZ-pane)
KinematicError delta_calcAngleYZ(float x0, float y0, float z0, float& theta) {
float y1 = -0.5 * 0.57735 * f; // f/2 * tg 30
@@ -361,43 +354,15 @@ float three_axis_dist(float* point1, float* point2) {
return sqrt(((point1[0] - point2[0]) * (point1[0] - point2[0])) + ((point1[1] - point2[1]) * (point1[1] - point2[1])) +
((point1[2] - point2[2]) * (point1[2] - point2[2])));
}
-// called by reporting for WPos status
-void forward_kinematics(float* position) {
- float calc_fwd[N_AXIS];
- int status;
- read_settings();
-
- // convert the system position in steps to radians
- float position_radians[N_AXIS];
- int32_t position_steps[N_AXIS]; // Copy current state of the system position variable
- memcpy(position_steps, sys_position, sizeof(sys_position));
- system_convert_array_steps_to_mpos(position_radians, position_steps);
-
- // grbl_msg_sendf(
- // CLIENT_SERIAL, MsgLevel::Info, "Fwd Kin Angs %1.3f, %1.3f, %1.3f ", position_radians[0], position_radians[1], position_radians[2]);
-
- // detmine the position of the end effector joint center.
- status = calc_forward_kinematics(position_radians, calc_fwd);
-
- if (status == 0) {
- // apply offsets and set the returned values
- position[X_AXIS] = calc_fwd[X_AXIS] - gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS];
- position[Y_AXIS] = calc_fwd[Y_AXIS] - gc_state.coord_system[Y_AXIS] + gc_state.coord_offset[Y_AXIS];
- position[Z_AXIS] = calc_fwd[Z_AXIS] - gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS];
- } else {
- grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "MSG:Fwd Kin Error");
- }
-}
-
-bool kinematics_pre_homing(uint8_t cycle_mask) { // true = do not continue with normal Grbl homing
-#ifdef USE_CUSTOM_HOMING
- return true;
-#else
- //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "kinematics_pre_homing");
- return false;
-#endif
-}
+// bool kinematics_pre_homing(uint8_t cycle_mask) { // true = do not continue with normal Grbl homing
+// #ifdef USE_CUSTOM_HOMING
+// return true;
+// #else
+// //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "kinematics_pre_homing");
+// return false;
+// #endif
+// }
void kinematics_post_homing() {
#ifdef USE_CUSTOM_HOMING
@@ -407,9 +372,7 @@ void kinematics_post_homing() {
last_angle[Y_AXIS] = sys_position[Y_AXIS] / axis_settings[Y_AXIS]->steps_per_mm->get();
last_angle[Z_AXIS] = sys_position[Z_AXIS] / axis_settings[Z_AXIS]->steps_per_mm->get();
- read_settings();
-
- calc_forward_kinematics(last_angle, last_cartesian);
+ motors_to_cartesian(last_cartesian, last_angle, 3);
// grbl_msg_sendf(CLIENT_SERIAL,
// MsgLevel::Info,
diff --git a/Grbl_Esp32/Custom/polar_coaster.cpp b/Grbl_Esp32/Custom/polar_coaster.cpp
index 85cf3f8a..7041fbb0 100644
--- a/Grbl_Esp32/Custom/polar_coaster.cpp
+++ b/Grbl_Esp32/Custom/polar_coaster.cpp
@@ -85,9 +85,8 @@ void kinematics_post_homing() {
*/
-void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
- //static float last_angle = 0;
- //static float last_radius = 0;
+
+bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
float dx, dy, dz; // distances in each cartesian axis
float p_dx, p_dy, p_dz; // distances in each polar axis
float dist, polar_dist; // the distances in both systems...used to determine feed rate
@@ -139,11 +138,19 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
// end determining new feed rate
polar[RADIUS_AXIS] += x_offset;
polar[Z_AXIS] += z_offset;
+
+ // mc_line() returns false if a jog is cancelled.
+ // In that case we stop sending segments to the planner.
+ if (!mc_line(polar, pl_data)) {
+ return false;
+ }
+
+ //
last_radius = polar[RADIUS_AXIS];
last_angle = polar[POLAR_AXIS];
- mc_line(polar, pl_data);
}
// TO DO don't need a feedrate for rapids
+ return true;
}
/*
@@ -159,18 +166,10 @@ position = the current machine position
converted = position with forward kinematics applied.
*/
-void forward_kinematics(float* position) {
- float original_position[N_AXIS]; // temporary storage of original
- float print_position[N_AXIS];
- int32_t current_position[N_AXIS]; // Copy current state of the system position variable
- memcpy(current_position, sys_position, sizeof(sys_position));
- system_convert_array_steps_to_mpos(print_position, current_position);
- original_position[X_AXIS] = print_position[X_AXIS] - gc_state.coord_system[X_AXIS] + gc_state.coord_offset[X_AXIS];
- original_position[Y_AXIS] = print_position[Y_AXIS] - gc_state.coord_system[Y_AXIS] + gc_state.coord_offset[Y_AXIS];
- original_position[Z_AXIS] = print_position[Z_AXIS] - gc_state.coord_system[Z_AXIS] + gc_state.coord_offset[Z_AXIS];
- position[X_AXIS] = cos(radians(original_position[Y_AXIS])) * original_position[X_AXIS] * -1;
- position[Y_AXIS] = sin(radians(original_position[Y_AXIS])) * original_position[X_AXIS];
- position[Z_AXIS] = original_position[Z_AXIS]; // unchanged
+void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
+ cartesian[X_AXIS] = cos(radians(motors[Y_AXIS])) * motors[X_AXIS] * -1;
+ cartesian[Y_AXIS] = sin(radians(motors[Y_AXIS])) * motors[X_AXIS];
+ cartesian[Z_AXIS] = motors[Z_AXIS]; // unchanged
}
// helper functions
diff --git a/Grbl_Esp32/src/data/favicon.ico b/Grbl_Esp32/data/favicon.ico
similarity index 100%
rename from Grbl_Esp32/src/data/favicon.ico
rename to Grbl_Esp32/data/favicon.ico
diff --git a/Grbl_Esp32/src/data/index.html.gz b/Grbl_Esp32/data/index.html.gz
similarity index 100%
rename from Grbl_Esp32/src/data/index.html.gz
rename to Grbl_Esp32/data/index.html.gz
diff --git a/Grbl_Esp32/src/Config.h b/Grbl_Esp32/src/Config.h
index 50b014f8..ffba4148 100644
--- a/Grbl_Esp32/src/Config.h
+++ b/Grbl_Esp32/src/Config.h
@@ -47,14 +47,16 @@ Some features should not be changed. See notes below.
// that the machine file might choose to undefine.
// Note: HOMING_CYCLES are now settings
+#define SUPPORT_TASK_CORE 1 // Reference: CONFIG_ARDUINO_RUNNING_CORE = 1
// Inverts pin logic of the control command pins based on a mask. This essentially means you can use
// normally-closed switches on the specified pins, rather than the default normally-open switches.
-// The mask order is Cycle Start | Feed Hold | Reset | Safety Door
+// The mask order is ...
+// Macro3 | Macro2 | Macro 1| Macr0 |Cycle Start | Feed Hold | Reset | Safety Door
// For example B1101 will invert the function of the Reset pin.
-#define INVERT_CONTROL_PIN_MASK B1111
+#define INVERT_CONTROL_PIN_MASK B00001111
-#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
+// #define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
#define USE_RMT_STEPS
@@ -85,8 +87,6 @@ const int MAX_N_AXIS = 6;
# define LIMIT_MASK B0
#endif
-#define GRBL_MSG_LEVEL MsgLevel::Info // what level of [MSG:....] do you want to see 0=all off
-
// Serial baud rate
// OK to change, but the ESP32 boot text is 115200, so you will not see that is your
// serial monitor, sender, etc uses a different value than 115200
@@ -128,7 +128,7 @@ const int MAX_N_AXIS = 6;
// "in the clear" over unsecured channels. It should be treated as a
// "friendly suggestion" to prevent unwitting dangerous actions, rather than
// as effective security against malice.
-//#define ENABLE_AUTHENTICATION
+// #define ENABLE_AUTHENTICATION
//CONFIGURE_EYECATCH_END (DO NOT MODIFY THIS LINE)
#ifdef ENABLE_AUTHENTICATION
@@ -258,11 +258,6 @@ static const uint8_t NHomingLocateCycle = 1; // Integer (1-128)
// previous tool path, as if nothing happened.
#define ENABLE_SAFETY_DOOR_INPUT_PIN // ESP32 Leave this enabled for now .. code for undefined not ready
-// After the safety door switch has been toggled and restored, this setting sets the power-up delay
-// between restoring the spindle and coolant and resuming the cycle.
-const double SAFETY_DOOR_SPINDLE_DELAY = 4.0; // Float (seconds)
-const double SAFETY_DOOR_COOLANT_DELAY = 1.0; // Float (seconds)
-
// Inverts select limit pin states based on the following mask. This effects all limit pin functions,
// such as hard limits and homing. However, this is different from overall invert limits setting.
// This build option will invert only the limit pins defined here, and then the invert limits setting
@@ -451,17 +446,7 @@ const int DWELL_TIME_STEP = 50; // Integer (1-255) (milliseconds)
// While this is experimental, it is intended to be the future default method after testing
//#define USE_RMT_STEPS
-// Creates a delay between the direction pin setting and corresponding step pulse by creating
-// another interrupt (Timer2 compare) to manage it. The main Grbl interrupt (Timer1 compare)
-// sets the direction pins, and does not immediately set the stepper pins, as it would in
-// normal operation. The Timer2 compare fires next to set the stepper pins after the step
-// pulse delay time, and Timer2 overflow will complete the step pulse, except now delayed
-// by the step pulse time plus the step pulse delay. (Thanks langwadt for the idea!)
-// NOTE: Uncomment to enable. The recommended delay must be > 3us, and, when added with the
-// user-supplied step pulse time, the total time must not exceed 127us. Reported successful
-// values for certain setups have ranged from 5 to 20us.
-// must use #define USE_RMT_STEPS for this to work
-//#define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled.
+// STEP_PULSE_DELAY is now a setting...$Stepper/Direction/Delay
// The number of linear motions in the planner buffer to be planned at any give time. The vast
// majority of RAM that Grbl uses is based on this buffer size. Only increase if there is extra
@@ -582,8 +567,8 @@ const int DEBOUNCE_PERIOD = 32; // in milliseconds default 32 microseconds
// Configure options for the parking motion, if enabled.
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
const double PARKING_TARGET = -5.0; // Parking axis target. In mm, as machine coordinate.
-const double PARKING_RATE = 500.0; // Parking fast rate after pull-out in mm/min.
-const double PARKING_PULLOUT_RATE = 100.0; // Pull-out/plunge slow feed rate in mm/min.
+const double PARKING_RATE = 800.0; // Parking fast rate after pull-out in mm/min.
+const double PARKING_PULLOUT_RATE = 250.0; // Pull-out/plunge slow feed rate in mm/min.
const double PARKING_PULLOUT_INCREMENT = 5.0; // Spindle pull-out and plunge distance in mm. Incremental distance.
// Must be positive value or equal to zero.
diff --git a/Grbl_Esp32/src/CustomCode.cpp b/Grbl_Esp32/src/CustomCode.cpp
index 7ee3f88a..f0e0e626 100644
--- a/Grbl_Esp32/src/CustomCode.cpp
+++ b/Grbl_Esp32/src/CustomCode.cpp
@@ -6,3 +6,7 @@
#ifdef CUSTOM_CODE_FILENAME
# include CUSTOM_CODE_FILENAME
#endif
+
+#ifdef DISPLAY_CODE_FILENAME
+# include DISPLAY_CODE_FILENAME
+#endif
\ No newline at end of file
diff --git a/Grbl_Esp32/src/Defaults.h b/Grbl_Esp32/src/Defaults.h
index 6ca3728c..9c5ac586 100644
--- a/Grbl_Esp32/src/Defaults.h
+++ b/Grbl_Esp32/src/Defaults.h
@@ -42,6 +42,14 @@
# define DEFAULT_STEP_PULSE_MICROSECONDS 3 // $0
#endif
+#ifndef DEFAULT_STEP_ENABLE_DELAY
+# define DEFAULT_STEP_ENABLE_DELAY 0
+#endif
+
+#ifndef STEP_PULSE_DELAY
+# define STEP_PULSE_DELAY 0
+#endif
+
#ifndef DEFAULT_STEPPER_IDLE_LOCK_TIME
# define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // $1 msec (0-254, 255 keeps steppers enabled)
#endif
@@ -159,6 +167,10 @@
# define DEFAULT_LASER_MODE 0 // false
#endif
+#ifndef DEFAULT_LASER_FULL_POWER
+# define DEFAULT_LASER_FULL_POWER 1000
+#endif
+
#ifndef DEFAULT_SPINDLE_RPM_MAX // $30
# define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#endif
@@ -183,6 +195,10 @@
# define DEFAULT_SPINDLE_DELAY_SPINUP 0
#endif
+#ifndef DEFAULT_COOLANT_DELAY_TURNON
+# define DEFAULT_COOLANT_DELAY_TURNON 1.0
+#endif
+
#ifndef DEFAULT_SPINDLE_DELAY_SPINDOWN
# define DEFAULT_SPINDLE_DELAY_SPINDOWN 0
#endif
@@ -457,6 +473,10 @@
// This can eliminate checking to see if the pin is defined because
// the overridden pinMode and digitalWrite functions will deal with it.
+#ifndef SDCARD_DET_PIN
+# define SDCARD_DET_PIN UNDEFINED_PIN
+#endif
+
#ifndef STEPPERS_DISABLE_PIN
# define STEPPERS_DISABLE_PIN UNDEFINED_PIN
#endif
@@ -643,3 +663,19 @@
#ifndef USER_ANALOG_PIN_3_FREQ
# define USER_ANALOG_PIN_3_FREQ 5000
#endif
+
+#ifndef DEFAULT_USER_MACRO0
+# define DEFAULT_USER_MACRO0 ""
+#endif
+
+#ifndef DEFAULT_USER_MACRO1
+# define DEFAULT_USER_MACRO1 ""
+#endif
+
+#ifndef DEFAULT_USER_MACRO2
+# define DEFAULT_USER_MACRO2 ""
+#endif
+
+#ifndef DEFAULT_USER_MACRO3
+# define DEFAULT_USER_MACRO3 ""
+#endif
diff --git a/Grbl_Esp32/src/Eeprom.cpp b/Grbl_Esp32/src/Eeprom.cpp
deleted file mode 100644
index 048524a5..00000000
--- a/Grbl_Esp32/src/Eeprom.cpp
+++ /dev/null
@@ -1,82 +0,0 @@
-/*
- Eeprom.cpp - Coordinate data stored in EEPROM
- Part of Grbl
- Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
-
- 2018 - Bart Dring This file was modifed for use on the ESP32
- CPU. Do not use this with Grbl for atMega328P
-
- Grbl 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. If not, see .
-*/
-
-#include "Grbl.h"
-#include "Eeprom.h"
-
-void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size) {
- unsigned char checksum = 0;
- for (; size > 0; size--) {
- unsigned char data = static_cast(*source++);
- // Note: This checksum calculation is broken as described below.
- checksum = (checksum << 1) || (checksum >> 7);
- checksum += data;
- EEPROM.write(destination++, *(source++));
- }
- EEPROM.write(destination, checksum);
- EEPROM.commit();
-}
-
-int memcpy_from_eeprom_with_old_checksum(char* destination, unsigned int source, unsigned int size) {
- unsigned char data, checksum = 0;
- for (; size > 0; size--) {
- data = EEPROM.read(source++);
- // Note: This checksum calculation is broken - the || should be just | -
- // thus making the checksum very weak.
- // We leave it as-is so we can read old data after a firmware upgrade.
- // The new storage format uses the tagged NVS mechanism, avoiding this bug.
- checksum = (checksum << 1) || (checksum >> 7);
- checksum += data;
- *(destination++) = data;
- }
- return (checksum == EEPROM.read(source));
-}
-int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size) {
- unsigned char data, checksum = 0;
- for (; size > 0; size--) {
- data = EEPROM.read(source++);
- checksum = (checksum << 1) | (checksum >> 7);
- checksum += data;
- *(destination++) = data;
- }
- return (checksum == EEPROM.read(source));
-}
-
-// Read selected coordinate data from EEPROM. Updates pointed coord_data value.
-// This is now a compatibility routine that is used to propagate coordinate data
-// in the old EEPROM format to the new tagged NVS format.
-bool old_settings_read_coord_data(uint8_t coord_select, float* coord_data) {
- uint32_t addr = coord_select * (sizeof(float) * N_AXIS + 1) + EEPROM_ADDR_PARAMETERS;
- if (!(memcpy_from_eeprom_with_old_checksum((char*)coord_data, addr, sizeof(float) * N_AXIS)) &&
- !(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float) * MAX_N_AXIS))) {
- // Reset with default zero vector
- clear_vector_float(coord_data);
- // The old code used to rewrite the zeroed data but now that is done
- // elsewhere, in a different format.
- return false;
- }
- return true;
-}
-
-// Allow iteration over CoordIndex values
-CoordIndex& operator ++ (CoordIndex& i) {
- i = static_cast(static_cast(i) + 1);
- return i;
-}
diff --git a/Grbl_Esp32/src/Eeprom.h b/Grbl_Esp32/src/Eeprom.h
deleted file mode 100644
index b3ed9998..00000000
--- a/Grbl_Esp32/src/Eeprom.h
+++ /dev/null
@@ -1,61 +0,0 @@
-#pragma once
-
-/*
- Eeprom.h - Header for system level commands and real-time processes
- Part of Grbl
- Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
-
- 2018 - Bart Dring This file was modifed for use on the ESP32
- CPU. Do not use this with Grbl for atMega328P
-
- Grbl 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. If not, see .
-*/
-
-// #include "Grbl.h"
-
-// Define EEPROM memory address location values for saved coordinate data.
-const int EEPROM_SIZE = 1024U;
-const int EEPROM_ADDR_PARAMETERS = 512U;
-
-//unsigned char eeprom_get_char(unsigned int addr);
-//void eeprom_put_char(unsigned int addr, unsigned char new_value);
-void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size);
-int memcpy_from_eeprom_with_checksum(char* destination, unsigned int source, unsigned int size);
-int memcpy_from_eeprom_with_old_checksum(char* destination, unsigned int source, unsigned int size);
-
-// Reads selected coordinate data from EEPROM
-bool old_settings_read_coord_data(uint8_t coord_select, float* coord_data);
-
-// Various places in the code access saved coordinate system data
-// by a small integer index according to the values below.
-enum CoordIndex : uint8_t{
- Begin = 0,
- G54 = Begin,
- G55,
- G56,
- G57,
- G58,
- G59,
- // To support 9 work coordinate systems it would be necessary to define
- // the following 3 and modify GCode.cpp to support G59.1, G59.2, G59.3
- // G59_1,
- // G59_2,
- // G59_3,
- NWCSystems,
- G28 = NWCSystems,
- G30,
- // G92_2,
- // G92_3,
- End,
-};
-// Allow iteration over CoordIndex values
-CoordIndex& operator ++ (CoordIndex& i);
diff --git a/Grbl_Esp32/src/Error.cpp b/Grbl_Esp32/src/Error.cpp
index 970124cc..b0401848 100644
--- a/Grbl_Esp32/src/Error.cpp
+++ b/Grbl_Esp32/src/Error.cpp
@@ -61,16 +61,16 @@ std::map ErrorNames = {
{ Error::GcodeG43DynamicAxisError, "Gcode G43 dynamic axis error" },
{ Error::GcodeMaxValueExceeded, "Gcode max value exceeded" },
{ Error::PParamMaxExceeded, "P param max exceeded" },
- { Error::SdFailedMount, "SD failed mount" },
- { Error::SdFailedRead, "SD failed read" },
- { Error::SdFailedOpenDir, "SD failed to open directory" },
- { Error::SdDirNotFound, "SD directory not found" },
- { Error::SdFileEmpty, "SD file empty" },
- { Error::SdFileNotFound, "SD file not found" },
- { Error::SdFailedOpenFile, "SD failed to open file" },
- { Error::SdFailedBusy, "SD is busy" },
- { Error::SdFailedDelDir, "SD failed to delete directory" },
- { Error::SdFailedDelFile, "SD failed to delete file" },
+ { Error::FsFailedMount, "Failed to mount device" },
+ { Error::FsFailedRead, "Failed to read" },
+ { Error::FsFailedOpenDir, "Failed to open directory" },
+ { Error::FsDirNotFound, "Directory not found" },
+ { Error::FsFileEmpty, "File empty" },
+ { Error::FsFileNotFound, "File not found" },
+ { Error::FsFailedOpenFile, "Failed to open file" },
+ { Error::FsFailedBusy, "Device is busy" },
+ { Error::FsFailedDelDir, "Failed to delete directory" },
+ { Error::FsFailedDelFile, "Failed to delete file" },
{ Error::BtFailBegin, "Bluetooth failed to start" },
{ Error::WifiFailBegin, "WiFi failed to start" },
{ Error::NumberRange, "Number out of range for setting" },
@@ -79,5 +79,7 @@ std::map ErrorNames = {
{ Error::NvsSetFailed, "Failed to store setting" },
{ Error::NvsGetStatsFailed, "Failed to get setting status" },
{ Error::AuthenticationFailed, "Authentication failed!" },
+ { Error::AnotherInterfaceBusy, "Another interface is busy" },
{ Error::BadPinSpecification, "Bad Pin Specification" },
+ { Error::JogCancelled, "Jog Cancelled" },
};
diff --git a/Grbl_Esp32/src/Error.h b/Grbl_Esp32/src/Error.h
index 269c064b..733fd973 100644
--- a/Grbl_Esp32/src/Error.h
+++ b/Grbl_Esp32/src/Error.h
@@ -64,16 +64,16 @@ enum class Error : uint8_t {
GcodeG43DynamicAxisError = 37,
GcodeMaxValueExceeded = 38,
PParamMaxExceeded = 39,
- SdFailedMount = 60, // SD Failed to mount
- SdFailedRead = 61, // SD Failed to read file
- SdFailedOpenDir = 62, // SD card failed to open directory
- SdDirNotFound = 63, // SD Card directory not found
- SdFileEmpty = 64, // SD Card directory not found
- SdFileNotFound = 65, // SD Card file not found
- SdFailedOpenFile = 66, // SD card failed to open file
- SdFailedBusy = 67, // SD card is busy
- SdFailedDelDir = 68,
- SdFailedDelFile = 69,
+ FsFailedMount = 60, // SD Failed to mount
+ FsFailedRead = 61, // SD Failed to read file
+ FsFailedOpenDir = 62, // SD card failed to open directory
+ FsDirNotFound = 63, // SD Card directory not found
+ FsFileEmpty = 64, // SD Card directory not found
+ FsFileNotFound = 65, // SD Card file not found
+ FsFailedOpenFile = 66, // SD card failed to open file
+ FsFailedBusy = 67, // SD card is busy
+ FsFailedDelDir = 68,
+ FsFailedDelFile = 69,
BtFailBegin = 70, // Bluetooth failed to start
WifiFailBegin = 71, // WiFi failed to start
NumberRange = 80, // Setting number range problem
@@ -83,6 +83,8 @@ enum class Error : uint8_t {
NvsGetStatsFailed = 101,
AuthenticationFailed = 110,
Eol = 111,
+ AnotherInterfaceBusy = 120,
+ JogCancelled = 130,
BadPinSpecification = 150,
};
diff --git a/Grbl_Esp32/src/GCode.cpp b/Grbl_Esp32/src/GCode.cpp
index bc2950b6..19a48f23 100644
--- a/Grbl_Esp32/src/GCode.cpp
+++ b/Grbl_Esp32/src/GCode.cpp
@@ -26,6 +26,12 @@
#include "MachineConfig.h"
+// Allow iteration over CoordIndex values
+CoordIndex& operator++(CoordIndex& i) {
+ i = static_cast(static_cast(i) + 1);
+ return i;
+}
+
// NOTE: Max line number is defined by the g-code standard to be 99999. It seems to be an
// arbitrary value, and some GUIs may require more. So we increased it based on a max safe
// value when converting a float (7.2 digit precision)s to an integer.
@@ -236,6 +242,7 @@ Error gc_execute_line(char* line, uint8_t client) {
mantissa = 0; // Set to zero to indicate valid non-integer G command.
break;
default:
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "M4 requires laser mode or a reversable spindle");
FAIL(Error::GcodeUnsupportedCommand);
// not reached
break;
@@ -489,9 +496,7 @@ Error gc_execute_line(char* line, uint8_t client) {
break;
case 6: // tool change
gc_block.modal.tool_change = ToolChange::Enable;
-#ifdef USE_TOOL_CHANGE
//user_tool_change(gc_state.tool);
-#endif
mg_word_bit = ModalGroup::MM6;
break;
case 7:
@@ -1282,14 +1287,16 @@ Error gc_execute_line(char* line, uint8_t client) {
FAIL(Error::InvalidJogCommand);
}
// Initialize planner data to current spindle and coolant modal state.
- pl_data->spindle_speed = gc_state.spindle_speed;
- pl_data->spindle = gc_state.modal.spindle;
- pl_data->coolant = gc_state.modal.coolant;
- Error status = jog_execute(pl_data, &gc_block);
- if (status == Error::Ok) {
+ pl_data->spindle_speed = gc_state.spindle_speed;
+ pl_data->spindle = gc_state.modal.spindle;
+ pl_data->coolant = gc_state.modal.coolant;
+ bool cancelledInflight = false;
+ Error status = jog_execute(pl_data, &gc_block, &cancelledInflight);
+ if (status == Error::Ok && !cancelledInflight) {
memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz));
}
- return status;
+ // JogCancelled is not reported as a GCode error
+ return status == Error::JogCancelled ? Error::Ok : status;
}
// If in laser mode, setup laser power based on current and past parser conditions.
if (MachineConfig::instance()->_laserMode) {
@@ -1356,9 +1363,7 @@ Error gc_execute_line(char* line, uint8_t client) {
// gc_state.tool = gc_block.values.t;
// [6. Change tool ]: NOT SUPPORTED
if (gc_block.modal.tool_change == ToolChange::Enable) {
-#ifdef USE_TOOL_CHANGE
user_tool_change(gc_state.tool);
-#endif
}
// [7. Spindle control ]:
if (gc_state.modal.spindle != gc_block.modal.spindle) {
@@ -1396,10 +1401,11 @@ Error gc_execute_line(char* line, uint8_t client) {
if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync) ||
(gc_block.modal.io_control == IoControl::DigitalOnImmediate) || (gc_block.modal.io_control == IoControl::DigitalOffImmediate)) {
if (gc_block.values.p < MaxUserDigitalPin) {
- if (!sys_io_control(
- bit((int)gc_block.values.p),
- (gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOnImmediate),
- (gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync))) {
+ if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync)) {
+ protocol_buffer_synchronize();
+ }
+ bool turnOn = gc_block.modal.io_control == IoControl::DigitalOnSync || gc_block.modal.io_control == IoControl::DigitalOnImmediate;
+ if (!sys_set_digital((int)gc_block.values.p, turnOn)) {
FAIL(Error::PParamMaxExceeded);
}
} else {
@@ -1409,8 +1415,12 @@ Error gc_execute_line(char* line, uint8_t client) {
if ((gc_block.modal.io_control == IoControl::SetAnalogSync) || (gc_block.modal.io_control == IoControl::SetAnalogImmediate)) {
if (gc_block.values.e < MaxUserDigitalPin) {
gc_block.values.q = constrain(gc_block.values.q, 0.0, 100.0); // force into valid range
- if (!sys_pwm_control(bit((int)gc_block.values.e), gc_block.values.q, (gc_block.modal.io_control == IoControl::SetAnalogSync)))
+ if (gc_block.modal.io_control == IoControl::SetAnalogSync) {
+ protocol_buffer_synchronize();
+ }
+ if (!sys_set_analog((int)gc_block.values.e, gc_block.values.q)) {
FAIL(Error::PParamMaxExceeded);
+ }
} else {
FAIL(Error::PParamMaxExceeded);
}
@@ -1425,7 +1435,7 @@ Error gc_execute_line(char* line, uint8_t client) {
#endif
// [10. Dwell ]:
if (gc_block.non_modal_command == NonModal::Dwell) {
- mc_dwell(gc_block.values.p);
+ mc_dwell(int32_t(gc_block.values.p * 1000.0f));
}
// [11. Set active plane ]:
gc_state.modal.plane_select = gc_block.modal.plane_select;
@@ -1475,9 +1485,9 @@ Error gc_execute_line(char* line, uint8_t client) {
// and absolute and incremental modes.
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
if (axis_command != AxisCommand::None) {
- mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
+ cartesian_to_motors(gc_block.values.xyz, pl_data, gc_state.position);
}
- mc_line_kins(coord_data, pl_data, gc_state.position);
+ cartesian_to_motors(coord_data, pl_data, gc_state.position);
memcpy(gc_state.position, coord_data, sizeof(gc_state.position));
break;
case NonModal::SetHome0:
@@ -1505,12 +1515,10 @@ Error gc_execute_line(char* line, uint8_t client) {
if (axis_command == AxisCommand::MotionMode) {
GCUpdatePos gc_update_pos = GCUpdatePos::Target;
if (gc_state.modal.motion == Motion::Linear) {
- //mc_line(gc_block.values.xyz, pl_data);
- mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
+ cartesian_to_motors(gc_block.values.xyz, pl_data, gc_state.position);
} else if (gc_state.modal.motion == Motion::Seek) {
pl_data->motion.rapidMotion = 1; // Set rapid motion flag.
- //mc_line(gc_block.values.xyz, pl_data);
- mc_line_kins(gc_block.values.xyz, pl_data, gc_state.position);
+ cartesian_to_motors(gc_block.values.xyz, pl_data, gc_state.position);
} else if ((gc_state.modal.motion == Motion::CwArc) || (gc_state.modal.motion == Motion::CcwArc)) {
mc_arc(gc_block.values.xyz,
pl_data,
@@ -1595,9 +1603,7 @@ Error gc_execute_line(char* line, uint8_t client) {
MachineConfig::instance()->_coolant->off();
}
report_feedback_message(Message::ProgramEnd);
-#ifdef USE_M30
user_m30();
-#endif
break;
}
gc_state.modal.program_flow = ProgramFlow::Running; // Reset program flow.
diff --git a/Grbl_Esp32/src/GCode.h b/Grbl_Esp32/src/GCode.h
index c637605d..64f09154 100644
--- a/Grbl_Esp32/src/GCode.h
+++ b/Grbl_Esp32/src/GCode.h
@@ -236,6 +236,32 @@ enum GCParserFlags {
GCParserLaserIsMotion = bit(7),
};
+// Various places in the code access saved coordinate system data
+// by a small integer index according to the values below.
+enum CoordIndex : uint8_t{
+ Begin = 0,
+ G54 = Begin,
+ G55,
+ G56,
+ G57,
+ G58,
+ G59,
+ // To support 9 work coordinate systems it would be necessary to define
+ // the following 3 and modify GCode.cpp to support G59.1, G59.2, G59.3
+ // G59_1,
+ // G59_2,
+ // G59_3,
+ NWCSystems,
+ G28 = NWCSystems,
+ G30,
+ // G92_2,
+ // G92_3,
+ End,
+};
+
+// Allow iteration over CoordIndex values
+CoordIndex& operator ++ (CoordIndex& i);
+
// NOTE: When this struct is zeroed, the 0 values in the above types set the system defaults.
typedef struct {
Motion motion; // {G0,G1,G2,G3,G38.2,G80}
diff --git a/Grbl_Esp32/src/Grbl.cpp b/Grbl_Esp32/src/Grbl.cpp
index ca5d12c7..d6af9b3b 100644
--- a/Grbl_Esp32/src/Grbl.cpp
+++ b/Grbl_Esp32/src/Grbl.cpp
@@ -34,7 +34,8 @@ void grbl_init() {
Serial.println("Initializing serial communications...");
// Setup serial baud rate and interrupts
- serial_init();
+ client_init();
+ display_init();
grbl_msg_sendf(
CLIENT_SERIAL, MsgLevel::Info, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
@@ -66,10 +67,8 @@ void grbl_init() {
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
-#ifdef USE_MACHINE_INIT
machine_init(); // user supplied function for special initialization
-#endif
- // Initialize system state.
+ // Initialize system state.
#ifdef FORCE_INITIALIZATION_ALARM
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
sys.state = State::Alarm;
@@ -131,7 +130,7 @@ static void reset_variables() {
sys_rt_s_override = SpindleSpeedOverride::Default;
// Reset Grbl primary systems.
- serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
+ client_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
gc_init(); // Set g-code parser to default state
spindle->stop();
@@ -144,6 +143,10 @@ static void reset_variables() {
plan_sync_position();
gc_sync_position();
report_init_message(CLIENT_ALL);
+
+ // used to keep track of a jog command sent to mc_line() so we can cancel it.
+ // this is needed if a jogCancel comes along after we have already parsed a jog and it is in-flight.
+ sys_pl_data_inflight = NULL;
}
void run_once() {
@@ -161,6 +164,14 @@ void run_once() {
}
}
+void __attribute__((weak)) machine_init() {}
+
+void __attribute__((weak)) display_init() {}
+
+void __attribute__((weak)) user_m30() {}
+
+void __attribute__((weak)) user_tool_change(uint8_t new_tool) {}
+
/*
setup() and loop() in the Arduino .ino implements this control flow:
diff --git a/Grbl_Esp32/src/Grbl.h b/Grbl_Esp32/src/Grbl.h
index 9ef5069b..9dfe14d7 100644
--- a/Grbl_Esp32/src/Grbl.h
+++ b/Grbl_Esp32/src/Grbl.h
@@ -41,7 +41,6 @@ const char* const GRBL_VERSION_BUILD = "20210326";
#include "Defaults.h"
#include "Error.h"
-#include "Eeprom.h"
#include "WebUI/Authentication.h"
#include "WebUI/Commands.h"
#include "Probe.h"
@@ -53,8 +52,9 @@ const char* const GRBL_VERSION_BUILD = "20210326";
#include "Limits.h"
#include "MotionControl.h"
#include "Protocol.h"
-#include "Report.h"
+#include "Uart.h"
#include "Serial.h"
+#include "Report.h"
#include "Pin.h"
#include "Spindles/Spindle.h"
#include "Stepper.h"
@@ -91,28 +91,22 @@ const char* const GRBL_VERSION_BUILD = "20210326";
void grbl_init();
void run_once();
-// Called if USE_MACHINE_INIT is defined
+// Weak definitions that can be overridden
void machine_init();
-
-// Called if USE_CUSTOM_HOMING is defined
bool user_defined_homing(uint8_t cycle_mask);
-// Called if USE_KINEMATICS is defined
+// weak definitions in MotionControl.cpp
+bool inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
+bool kinematics_pre_homing(uint8_t cycle_mask);
+void kinematics_post_homing();
-void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position);
-bool kinematics_pre_homing(uint8_t cycle_mask);
-void kinematics_post_homing();
-uint8_t kinematic_limits_check(float* target);
+bool limitsCheckTravel(float* target); // weak in Limits.cpp; true if out of range
-// Called if USE_FWD_KINEMATICS is defined
void inverse_kinematics(float* position); // used to return a converted value
void forward_kinematics(float* position);
-// Called if MACRO_BUTTON_0_PIN or MACRO_BUTTON_1_PIN or MACRO_BUTTON_2_PIN is defined
void user_defined_macro(uint8_t index);
-// Called if USE_M30 is defined
void user_m30();
-// Called if USE_TOOL_CHANGE is defined
void user_tool_change(uint8_t new_tool);
diff --git a/Grbl_Esp32/src/I2SOut.cpp b/Grbl_Esp32/src/I2SOut.cpp
index a81932f7..fb2ae70c 100644
--- a/Grbl_Esp32/src/I2SOut.cpp
+++ b/Grbl_Esp32/src/I2SOut.cpp
@@ -48,6 +48,7 @@
#include "WebUI/ESPResponse.h"
#include "Probe.h"
#include "System.h"
+#include "Serial.h"
#include "Report.h"
#include
@@ -534,7 +535,9 @@ static void IRAM_ATTR i2sOutTask(void* parameter) {
I2S_OUT_PULSER_EXIT_CRITICAL(); // Unlock pulser status
static UBaseType_t uxHighWaterMark = 0;
+# ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
+# endif
}
}
#endif
diff --git a/Grbl_Esp32/src/Jog.cpp b/Grbl_Esp32/src/Jog.cpp
index 1c0c3d00..03474c7a 100644
--- a/Grbl_Esp32/src/Jog.cpp
+++ b/Grbl_Esp32/src/Jog.cpp
@@ -24,11 +24,13 @@
#include "Grbl.h"
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
-Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
+// cancelledInflight will be set to true if was not added to parser due to a cancelJog.
+Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* cancelledInflight) {
// Initialize planner data struct for jogging motions.
// NOTE: Spindle and coolant are allowed to fully function with overrides during a jog.
pl_data->feed_rate = gc_block->values.f;
pl_data->motion.noFeedOverride = 1;
+ pl_data->is_jog = true;
#ifdef USE_LINE_NUMBERS
pl_data->line_number = gc_block->values.n;
#endif
@@ -37,12 +39,10 @@ Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block) {
return Error::TravelExceeded;
}
}
-// Valid jog command. Plan, set state, and execute.
-#ifndef USE_KINEMATICS
- mc_line(gc_block->values.xyz, pl_data);
-#else // else use kinematics
- inverse_kinematics(gc_block->values.xyz, pl_data, gc_state.position);
-#endif
+ // Valid jog command. Plan, set state, and execute.
+ if (!cartesian_to_motors(gc_block->values.xyz, pl_data, gc_state.position)) {
+ return Error::JogCancelled;
+ }
if (sys.state == State::Idle) {
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
diff --git a/Grbl_Esp32/src/Jog.h b/Grbl_Esp32/src/Jog.h
index 59307834..1867871e 100644
--- a/Grbl_Esp32/src/Jog.h
+++ b/Grbl_Esp32/src/Jog.h
@@ -28,4 +28,5 @@
const int JOG_LINE_NUMBER = 0;
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
-Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block);
+// cancelledInflight will be set to true if was not added to parser due to a cancelJog.
+Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* cancelledInflight);
diff --git a/Grbl_Esp32/src/Limits.cpp b/Grbl_Esp32/src/Limits.cpp
index 2b01a681..ea541ad0 100644
--- a/Grbl_Esp32/src/Limits.cpp
+++ b/Grbl_Esp32/src/Limits.cpp
@@ -56,10 +56,12 @@ void IRAM_ATTR isr_limit_switches(void* /*unused */) {
# ifdef HARD_LIMIT_FORCE_STATE_CHECK
// Check limit pin state.
if (limits_get_state()) {
+ grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Hard limits");
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}
# else
+ grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Hard limits");
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
# endif
@@ -103,7 +105,6 @@ void limits_go_home(uint8_t cycle_mask) {
// Initialize variables used for homing computations.
uint8_t n_cycle = (2 * n_homing_locate_cycle + 1);
uint8_t step_pin[MAX_N_AXIS];
- float target[MAX_N_AXIS];
float max_travel = 0.0;
auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
@@ -111,8 +112,8 @@ void limits_go_home(uint8_t cycle_mask) {
// Initialize step pin masks
step_pin[idx] = bit(idx);
if (bit_istrue(cycle_mask, bit(idx))) {
- // Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
- max_travel = MAX(max_travel, (HOMING_AXIS_SEARCH_SCALAR)* MachineConfig::instance()->_axes->_axis[idx]->_maxTravel);
+ // Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
+ max_travel = MAX(max_travel, (HOMING_AXIS_SEARCH_SCALAR)*MachineConfig::instance()->_axes->_axis[idx]->_maxTravel);
}
}
// Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
@@ -121,7 +122,7 @@ void limits_go_home(uint8_t cycle_mask) {
uint8_t n_active_axis;
AxisMask limit_state, axislock;
do {
- system_convert_array_steps_to_mpos(target, sys_position);
+ float* target = system_get_mpos();
// Initialize and declare variables needed for homing routine.
axislock = 0;
n_active_axis = 0;
@@ -196,7 +197,8 @@ void limits_go_home(uint8_t cycle_mask) {
if (sys_rt_exec_alarm != ExecAlarm::None) {
MachineConfig::instance()->_axes->set_homing_mode(cycle_mask, false); // tell motors homing is done...failed
- mc_reset(); // Stop motors, if they are running.
+ grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Homing fail");
+ mc_reset(); // Stop motors, if they are running.
protocol_execute_realtime();
return;
} else {
@@ -249,7 +251,7 @@ void limits_go_home(uint8_t cycle_mask) {
}
}
}
- sys.step_control = {}; // Return step control to normal operation.
+ sys.step_control = {}; // Return step control to normal operation.
MachineConfig::instance()->_axes->set_homing_mode(cycle_mask, false); // tell motors homing is done
}
@@ -264,10 +266,8 @@ void limits_init() {
for (int gang_index = 0; gang_index < 2; gang_index++) {
Pin pin;
if ((pin = LimitPins[axis][gang_index]->get()) != Pin::UNDEFINED) {
-
#ifndef DISABLE_LIMIT_PIN_PULL_UP
- if (pin.capabilities().has(Pins::PinCapabilities::PullUp))
- {
+ if (pin.capabilities().has(Pins::PinCapabilities::PullUp)) {
mode = mode | Pin::Attr::PullUp;
}
#endif
@@ -356,6 +356,7 @@ void limits_soft_check(float* target) {
}
} while (sys.state != State::Idle);
}
+ grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Soft limits");
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
sys_rt_exec_alarm = ExecAlarm::SoftLimit; // Indicate soft limit critical event
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
@@ -372,12 +373,14 @@ void limitCheckTask(void* pvParameters) {
AxisMask switch_state;
switch_state = limits_get_state();
if (switch_state) {
- //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Limit Switch State %08d", switch_state);
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Debug, "Limit Switch State %08d", switch_state);
mc_reset(); // Initiate system kill.
sys_rt_exec_alarm = ExecAlarm::HardLimit; // Indicate hard limit critical event
}
static UBaseType_t uxHighWaterMark = 0;
+#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
+#endif
}
}
@@ -395,15 +398,24 @@ float limitsMinPosition(uint8_t axis) {
// Checks and reports if target array exceeds machine travel limits.
// Return true if exceeding limits
-bool limitsCheckTravel(float* target) {
+// Set $/MaxTravel=0 to selectively remove an axis from soft limit checks
+bool __attribute__((weak)) limitsCheckTravel(float* target) {
uint8_t idx;
auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
for (idx = 0; idx < n_axis; idx++) {
float max_mpos, min_mpos;
- if (target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) {
+ if ((target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) && axis_settings[idx]->max_travel->get() > 0) {
return true;
}
}
return false;
}
+
+bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
+ return (limit_pins[axis][gang_index] != UNDEFINED_PIN);
+}
+
+bool __attribute__((weak)) user_defined_homing(uint8_t cycle_mask) {
+ return false;
+}
diff --git a/Grbl_Esp32/src/Limits.h b/Grbl_Esp32/src/Limits.h
index 29ec710f..db22dde2 100644
--- a/Grbl_Esp32/src/Limits.h
+++ b/Grbl_Esp32/src/Limits.h
@@ -54,3 +54,6 @@ float limitsMinPosition(uint8_t axis);
// Internal factor used by limits_soft_check
bool limitsCheckTravel(float* target);
+
+// check if a switch has been defined
+bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index);
diff --git a/Grbl_Esp32/src/Machines/3axis_rs485.h b/Grbl_Esp32/src/Machines/3axis_rs485.h
deleted file mode 100644
index 48581b93..00000000
--- a/Grbl_Esp32/src/Machines/3axis_rs485.h
+++ /dev/null
@@ -1,59 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- 3axis_xyx.h
- Part of Grbl_ESP32
-
- This is a general XYZ-axis RS-485 CNC machine. The schematic is quite
- easy, you basically need a MAX485 wired through a logic level converter
- for the VFD, and a few pins wired through an ULN2803A to the external
- stepper drivers. It's common to have a dual gantry for the Y axis.
-
- Optional limit pins are slightly more difficult, as these require a
- Schmitt trigger and optocouplers.
-
- 2020 - Stefan de Bruijn
-
- 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 .
-*/
-
-#define MACHINE_NAME "ESP32_XYZ_RS485"
-#define X_STEP_PIN "gpio.4" // labeled X
-#define X_DIRECTION_PIN "gpio.16" // labeled X
-#define Y_STEP_PIN "gpio.17" // labeled Y
-#define Y_DIRECTION_PIN "gpio.18" // labeled Y
-#define Y2_STEP_PIN "gpio.19" // labeled Y2
-#define Y2_DIRECTION_PIN "gpio.21" // labeled Y2
-#define Z_STEP_PIN "gpio.22" // labeled Z
-#define Z_DIRECTION_PIN "gpio.23" // labeled Z
-
-#define SPINDLE_TYPE SpindleType::H2A
-#define VFD_RS485_TXD_PIN "gpio.13" // RS485 TX
-#define VFD_RS485_RTS_PIN "gpio.15" // RS485 RTS
-#define VFD_RS485_RXD_PIN "gpio.2" // RS485 RX
-
-#define X_LIMIT_PIN "gpio.33"
-#define Y_LIMIT_PIN "gpio.32"
-#define Y2_LIMIT_PIN "gpio.35"
-#define Z_LIMIT_PIN "gpio.34"
-
-// Set $Homing/Cycle0=X and $Homing/Cycle=XY
-
-#define PROBE_PIN "gpio.14" // labeled Probe
-#define CONTROL_RESET_PIN "gpio.27" // labeled Reset
-#define CONTROL_FEED_HOLD_PIN "gpio.26" // labeled Hold
-#define CONTROL_CYCLE_START_PIN "gpio.25" // labeled Start
-
-// #define VFD_DEBUG_MODE
diff --git a/Grbl_Esp32/src/Machines/6_pack_stepstick_XYZ_v1.h b/Grbl_Esp32/src/Machines/6_pack_stepstick_XYZ_v1.h
deleted file mode 100644
index 2ad008eb..00000000
--- a/Grbl_Esp32/src/Machines/6_pack_stepstick_XYZ_v1.h
+++ /dev/null
@@ -1,123 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- 6_pack_stepstick_XYZ_v1.h
-
- Covers all V1 versions V1p0, V1p1, etc
-
- Part of Grbl_ESP32
- Pin assignments for the ESP32 I2S 6-axis board
- 2018 - Bart Dring
- 2020 - Mitch Bradley
- 2020 - Michiyasu Odaki
- 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 .
-*/
-#define MACHINE_NAME "6 Pack Controller StepStick XYZ"
-
-#define N_AXIS 3
-
-// === Special Features
-
-// I2S (steppers & other output-only pins)
-#define USE_I2S_OUT
-#define USE_I2S_STEPS
-//#define DEFAULT_STEPPER ST_I2S_STATIC
-// === Default settings
-#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
-
-#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
-
-#define I2S_OUT_BCK "gpio.22"
-#define I2S_OUT_WS "gpio.17"
-#define I2S_OUT_DATA "gpio.21"
-
-
-// Motor Socket #1
-#define X_DISABLE_PIN "i2so.0"
-#define X_DIRECTION_PIN "i2so.1"
-#define X_STEP_PIN "i2so.2"
-
-// Motor Socket #2
-#define Y_DIRECTION_PIN "i2so.4"
-#define Y_STEP_PIN "i2so.5"
-#define Y_DISABLE_PIN "i2so.7"
-
-// Motor Socket #3
-#define Z_DISABLE_PIN "i2so.8"
-#define Z_DIRECTION_PIN "i2so.9"
-#define Z_STEP_PIN "i2so.10"
-
-/*
- Socket I/O reference
- The list of modules is here...
- https://github.com/bdring/6-Pack_CNC_Controller/wiki/CNC-I-O-Module-List
- Click on each module to get example for using the modules in the sockets
-
-
-Socket #1
-#1 "gpio.33"
-#2 "gpio.32"
-#3 "gpio.35" (input only)
-#4 "gpio.34" (input only)
-
-Socket #2
-#1 "gpio.2"
-#2 "gpio.25"
-#3 "gpio.39" (input only)
-#4 "gpio.36" (input only)
-
-Socket #3
-#1 "gpio.26"
-#2 "gpio.4"
-#3 "gpio.16"
-#4 "gpio.27"
-
-Socket #4
-#1 "gpio.14"
-#2 "gpio.13"
-#3 "gpio.15"
-#4 "gpio.12"
-
-Socket #5
-#1 "i2so.24" (output only)
-#2 "i2so.25" (output only)
-#3 "i2so.26" (output only)
-
-*/
-
-
-// 4x Input Module in Socket #1
-// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
-#define X_LIMIT_PIN "gpio.33"
-#define Y_LIMIT_PIN "gpio.32"
-#define Z_LIMIT_PIN "gpio.35"
-
-
-// // 4x Input Module in Socket #2
-// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
-// #define X_LIMIT_PIN "gpio.2"
-// #define Y_LIMIT_PIN "gpio.25"
-// #define Z_LIMIT_PIN "gpio.39"
-
-// // 4x Input Module in Socket #3
-// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
-// #define CONTROL_CYCLE_START_PIN "gpio.26"
-// #define CONTROL_FEED_HOLD_PIN "gpio.4"
-// #define CONTROL_RESET_PIN "gpio.16"
-// #define CONTROL_SAFETY_DOOR_PIN "gpio.27"
-// //#define INVERT_CONTROL_PIN_MASK B0000
-
-// ================= Setting Defaults ==========================
-#define DEFAULT_X_STEPS_PER_MM 800
-#define DEFAULT_Y_STEPS_PER_MM 800
-#define DEFAULT_Z_STEPS_PER_MM 800
diff --git a/Grbl_Esp32/src/Machines/Root_Controller_Root_4_Lite_RS485.h b/Grbl_Esp32/src/Machines/Root_Controller_Root_4_Lite_RS485.h
new file mode 100644
index 00000000..f9bb81ca
--- /dev/null
+++ b/Grbl_Esp32/src/Machines/Root_Controller_Root_4_Lite_RS485.h
@@ -0,0 +1,136 @@
+#pragma once
+// clang-format off
+
+/*
+ Root_Controller_Root_4_Lite_RS485.h
+
+ Covers initial release version
+
+ Part of Grbl_ESP32
+ Pin assignments for the ESP32 I2S Root Controller 6-axis board
+ 2018 - Bart Dring
+ 2020 - Mitch Bradley
+ 2020 - Michiyasu Odaki
+ 2020 - Pete Newbery
+ 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 .
+*/
+#define MACHINE_NAME "Root Controller 3 Axis XYYZ"
+
+#define N_AXIS 3
+
+// === Special Features
+
+//**I2S (steppers & other output-only pins)
+#define USE_I2S_OUT
+#define USE_I2S_STEPS
+//#define DEFAULT_STEPPER ST_I2S_STATIC
+#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
+
+//Setup I2S Clocking
+#define I2S_OUT_BCK "gpio.22"
+#define I2S_OUT_WS "gpio.21"
+#define I2S_OUT_DATA "gpio.12"
+
+
+//**Motor Socket #1
+#define X_DISABLE_PIN "i2so.7"
+#define X_DIRECTION_PIN "i2so.6"
+#define X_STEP_PIN "i2so.5"
+//**Motor Socket #2
+#define Y_DISABLE_PIN "i2so.4"
+#define Y_DIRECTION_PIN "i2so.3"
+#define Y_STEP_PIN "i2so.2"
+//**Motor Socket #3
+#define Y2_DISABLE_PIN "i2so.1"
+#define Y2_DIRECTION_PIN "i2so.0"
+#define Y2_STEP_PIN "i2so.15"
+//**Motor Socket #4
+#define Z_DISABLE_PIN "i2so.14"
+#define Z_DIRECTION_PIN "i2so.13"
+#define Z_STEP_PIN "i2so.12"
+
+//**Motion Control
+//200pulses/rev stepper motor with SFU1204 ballscrew with a pitch of 4mm
+//equates to 50 Steps/mm * micro stepping
+//Steps per MM
+#define DEFAULT_X_STEPS_PER_MM 800
+#define DEFAULT_Y_STEPS_PER_MM 800
+#define DEFAULT_Z_STEPS_PER_MM 1000 // 50 Steps/mm * micro stepping * belt ratio
+//**Max Feedrate
+#define DEFAULT_X_MAX_RATE 1000
+#define DEFAULT_Y_MAX_RATE 1000
+#define DEFAULT_Z_MAX_RATE 1000
+//**Acceleration
+#define DEFAULT_X_ACCELERATION 50
+#define DEFAULT_Y_ACCELERATION 50
+#define DEFAULT_Z_ACCELERATION 50
+//**Max travel
+#define DEFAULT_X_MAX_TRAVEL 220
+#define DEFAULT_Y_MAX_TRAVEL 278
+#define DEFAULT_Z_MAX_TRAVEL 60
+
+
+//**Storage
+#define ENABLE_SD_CARD
+
+//**Endstop pins
+#define X_LIMIT_PIN "gpio.2"
+#define Y_LIMIT_PIN "gpio.26"
+#define Y2_LIMIT_PIN "gpio.27"
+#define Z_LIMIT_PIN "gpio.14"
+#define PROBE_PIN "gpio.33"
+#define INVERT_CONTROL_PIN_MASK 1
+#define DEFAULT_INVERT_LIMIT_PINS 7 // Enable for NC switch types
+//**Homing Routine
+#define DEFAULT_HOMING_ENABLE 1
+#define DEFAULT_HOMING_DIR_MASK 0
+#define DEFAULT_SOFT_LIMIT_ENABLE 1
+#define DEFAULT_HARD_LIMIT_ENABLE 1
+#define DEFAULT_HOMING_SQUARED_AXES (bit(Y_AXIS))
+#define DEFAULT_HOMING_FEED_RATE 100
+#define DEFAULT_HOMING_SEEK_RATE 800
+#define DEFAULT_HOMING_PULLOFF 2
+#define HOMING_INIT_LOCK
+#define LIMITS_TWO_SWITCHES_ON_AXES 1
+#define DEFAULT_HOMING_CYCLE_0 (1<.
+*/
+
+#define MACHINE_NAME "TMC2209 4x Controller"
+
+#define N_AXIS 4
+
+#define TRINAMIC_UART_RUN_MODE TrinamicUartMode :: StealthChop
+#define TRINAMIC_UART_HOMING_MODE TrinamicUartMode :: StallGuard
+
+#define TMC_UART UART_NUM_1
+#define TMC_UART_RX "gpio.21"
+#define TMC_UART_TX "gpio.22"
+
+#define X_TRINAMIC_DRIVER 2209
+#define X_STEP_PIN "gpio.26"
+#define X_DIRECTION_PIN "gpio.27"
+#define X_RSENSE TMC2209_RSENSE_DEFAULT
+#define X_DRIVER_ADDRESS 0
+#define DEFAULT_X_MICROSTEPS 16
+
+#define Y_TRINAMIC_DRIVER 2209
+#define Y_STEP_PIN "gpio.33"
+#define Y_DIRECTION_PIN "gpio.32"
+#define Y_RSENSE TMC2209_RSENSE_DEFAULT
+#define Y_DRIVER_ADDRESS 1
+#define DEFAULT_Y_MICROSTEPS 16
+
+#define Z_TRINAMIC_DRIVER 2209
+#define Z_STEP_PIN "gpio.2"
+#define Z_DIRECTION_PIN "gpio.14"
+#define Z_RSENSE TMC2209_RSENSE_DEFAULT
+#define Z_DRIVER_ADDRESS 2
+#define DEFAULT_Z_MICROSTEPS 16
+
+#define A_TRINAMIC_DRIVER 2209
+#define A_STEP_PIN "gpio.16"
+#define A_DIRECTION_PIN "gpio.15"
+#define A_RSENSE TMC2209_RSENSE_DEFAULT
+#define A_DRIVER_ADDRESS 3
+#define DEFAULT_A_MICROSTEPS 16
+
+#define X_LIMIT_PIN "gpio.35"
+#define Y_LIMIT_PIN "gpio.34"
+#define Z_LIMIT_PIN "gpio.39"
+#define PROBE_PIN "gpio.36"
+
+// OK to comment out to use pin for other features
+#define STEPPERS_DISABLE_PIN "gpio.25"
+
+
+// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-5V-Buffered-Output-Module
+// https://github.com/bdring/6-Pack_CNC_Controller/wiki/Quad-MOSFET-Module
+#define USER_DIGITAL_PIN_0 "gpio.4" // M62 M63
+#define USER_DIGITAL_PIN_1 "gpio.13" // M62 M63
+#define USER_DIGITAL_PIN_2 "gpio.17" // M62 M63
+#define USER_DIGITAL_PIN_3 "gpio.12" // M62 M63
+
+
+// ===================== defaults ======================
+// https://github.com/bdring/Grbl_Esp32/wiki/Setting-Defaults
+
+#define DEFAULT_INVERT_PROBE_PIN 1
diff --git a/Grbl_Esp32/src/Machines/atari_1020.h b/Grbl_Esp32/src/Machines/atari_1020.h
index b82b1770..5978e7c5 100644
--- a/Grbl_Esp32/src/Machines/atari_1020.h
+++ b/Grbl_Esp32/src/Machines/atari_1020.h
@@ -140,11 +140,7 @@
#define ATARI_HOMING_ATTEMPTS 13
// tells grbl we have some special functions to call
-#define USE_MACHINE_INIT
-#define USE_CUSTOM_HOMING
-#define USE_TOOL_CHANGE
#define ATARI_TOOL_CHANGE_Z 5.0
-#define USE_M30 // use the user defined end of program
#ifndef atari_h
#define atari_h
diff --git a/Grbl_Esp32/src/Machines/fysetc_ant.h b/Grbl_Esp32/src/Machines/fysetc_ant.h
new file mode 100644
index 00000000..79607088
--- /dev/null
+++ b/Grbl_Esp32/src/Machines/fysetc_ant.h
@@ -0,0 +1,85 @@
+#pragma once
+// clang-format off
+
+/*
+ fysetc_ant.h
+ https://github.com/FYSETC/FYSETC-E4
+
+ 2020-12-03 B. Dring
+
+ This is a machine definition file to use the FYSETC E4 3D Printer controller
+ This is a 4 motor controller. This is setup for XYZA, but XYYZ, could also be used.
+ There are 5 inputs
+ The controller has outputs for a Fan, Hotbed and Extruder. There are mapped to
+ spindle, mist and flood coolant to drive an external relay.
+
+ 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 .
+*/
+
+#define MACHINE_NAME "FYSETC E4 3D Printer Controller"
+
+#define N_AXIS 4
+
+#define CUSTOM_CODE_FILENAME "../Custom/CoreXY.cpp"
+
+#define USE_KINEMATICS // there are kinematic equations for this machine
+
+#define TRINAMIC_RUN_MODE TrinamicMode :: StealthChop
+#define TRINAMIC_HOMING_MODE TrinamicMode :: StealthChop
+
+#define TMC_UART UART_NUM_1
+#define TMC_UART_RX GPIO_NUM_21
+#define TMC_UART_TX GPIO_NUM_22
+
+#define X_TRINAMIC_DRIVER 2209
+#define X_STEP_PIN GPIO_NUM_27
+#define X_DIRECTION_PIN GPIO_NUM_26
+#define X_RSENSE TMC2209_RSENSE_DEFAULT
+#define X_DRIVER_ADDRESS 1
+#define DEFAULT_X_MICROSTEPS 16
+
+#define Y_TRINAMIC_DRIVER 2209
+#define Y_STEP_PIN GPIO_NUM_33
+#define Y_DIRECTION_PIN GPIO_NUM_32
+#define Y_RSENSE TMC2209_RSENSE_DEFAULT
+#define Y_DRIVER_ADDRESS 3
+#define DEFAULT_Y_MICROSTEPS 16
+
+#define Z_TRINAMIC_DRIVER 2209
+#define Z_STEP_PIN GPIO_NUM_14
+#define Z_DIRECTION_PIN GPIO_NUM_12
+#define Z_RSENSE TMC2209_RSENSE_DEFAULT
+#define Z_DRIVER_ADDRESS 0
+#define DEFAULT_Z_MICROSTEPS 16
+
+#define A_TRINAMIC_DRIVER 2209
+#define A_STEP_PIN GPIO_NUM_16
+#define A_DIRECTION_PIN GPIO_NUM_17
+#define A_RSENSE TMC2209_RSENSE_DEFAULT
+#define A_DRIVER_ADDRESS 2
+#define DEFAULT_A_MICROSTEPS 16
+
+#define X_LIMIT_PIN GPIO_NUM_34
+#define Y_LIMIT_PIN GPIO_NUM_35
+#define Z_LIMIT_PIN GPIO_NUM_15
+#define A_LIMIT_PIN GPIO_NUM_36 // Labeled TB
+#define PROBE_PIN GPIO_NUM_39 // Labeled TE
+
+// OK to comment out to use pin for other features
+#define STEPPERS_DISABLE_PIN GPIO_NUM_25
+
+#define SPINDLE_TYPE SpindleType::RELAY
+#define SPINDLE_OUTPUT_PIN GPIO_NUM_13 // labeled Fan
+#define COOLANT_MIST_PIN GPIO_NUM_2 // Labeled Hotbed
+#define COOLANT_FLOOD_PIN GPIO_NUM_4 // Labeled Heater
diff --git a/Grbl_Esp32/src/Machines/fysetc_e4.h b/Grbl_Esp32/src/Machines/fysetc_e4.h
new file mode 100644
index 00000000..2ca9f9bb
--- /dev/null
+++ b/Grbl_Esp32/src/Machines/fysetc_e4.h
@@ -0,0 +1,81 @@
+#pragma once
+// clang-format off
+
+/*
+ fysetc_e4.h
+ https://github.com/FYSETC/FYSETC-E4
+
+ 2020-12-03 B. Dring
+
+ This is a machine definition file to use the FYSETC E4 3D Printer controller
+ This is a 4 motor controller. This is setup for XYZA, but XYYZ, could also be used.
+ There are 5 inputs
+ The controller has outputs for a Fan, Hotbed and Extruder. There are mapped to
+ spindle, mist and flood coolant to drive an external relay.
+
+ 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 .
+*/
+
+#define MACHINE_NAME "FYSETC E4 3D Printer Controller"
+
+#define N_AXIS 4
+
+#define TRINAMIC_RUN_MODE TrinamicMode :: StealthChop
+#define TRINAMIC_HOMING_MODE TrinamicMode :: StealthChop
+
+#define TMC_UART UART_NUM_1
+#define TMC_UART_RX "gpio.21"
+#define TMC_UART_TX "gpio.22 "
+
+#define X_TRINAMIC_DRIVER 2209
+#define X_STEP_PIN "gpio.27"
+#define X_DIRECTION_PIN "gpio.26"
+#define X_RSENSE TMC2209_RSENSE_DEFAULT
+#define X_DRIVER_ADDRESS 1
+#define DEFAULT_X_MICROSTEPS 16
+
+#define Y_TRINAMIC_DRIVER 2209
+#define Y_STEP_PIN "gpio.33"
+#define Y_DIRECTION_PIN "gpio.32"
+#define Y_RSENSE TMC2209_RSENSE_DEFAULT
+#define Y_DRIVER_ADDRESS 3
+#define DEFAULT_Y_MICROSTEPS 16
+
+#define Z_TRINAMIC_DRIVER 2209
+#define Z_STEP_PIN "gpio.14"
+#define Z_DIRECTION_PIN "gpio.12"
+#define Z_RSENSE TMC2209_RSENSE_DEFAULT
+#define Z_DRIVER_ADDRESS 0
+#define DEFAULT_Z_MICROSTEPS 16
+
+#define A_TRINAMIC_DRIVER 2209
+#define A_STEP_PIN "gpio.16"
+#define A_DIRECTION_PIN "gpio.17"
+#define A_RSENSE TMC2209_RSENSE_DEFAULT
+#define A_DRIVER_ADDRESS 2
+#define DEFAULT_A_MICROSTEPS 16
+
+#define X_LIMIT_PIN "gpio.34"
+#define Y_LIMIT_PIN "gpio.35"
+#define Z_LIMIT_PIN "gpio.15"
+#define A_LIMIT_PIN "gpio.36" // Labeled TB
+#define PROBE_PIN "gpio.39" // Labeled TE
+
+// OK to comment out to use pin for other features
+#define STEPPERS_DISABLE_PIN "gpio.25"
+
+#define SPINDLE_TYPE SpindleType::RELAY
+#define SPINDLE_OUTPUT_PIN "gpio.13" // labeled Fan
+#define COOLANT_MIST_PIN "gpio.2" // Labeled Hotbed
+#define COOLANT_FLOOD_PIN "gpio.4" // Labeled Heater
diff --git a/Grbl_Esp32/src/Machines/i2s_out_xxyyzz.h b/Grbl_Esp32/src/Machines/i2s_out_xxyyzz.h
deleted file mode 100644
index 9cdb982d..00000000
--- a/Grbl_Esp32/src/Machines/i2s_out_xxyyzz.h
+++ /dev/null
@@ -1,102 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- i2s_out_xxyyzz.h
- Part of Grbl_ESP32
- Pin assignments for the ESP32 I2S 6-axis board
- 2018 - Bart Dring
- 2020 - Mitch Bradley
- 2020 - Michiyasu Odaki
- 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 .
-*/
-
-#define MACHINE_NAME "ESP32 I2S XXYYZZ Axis Driver Board (StepStick)"
-
-#ifdef N_AXIS
- #undef N_AXIS
-#endif
-#define N_AXIS 3
-
-#ifdef ENABLE_SD_CARD
- #undef ENABLE_SD_CARD
-#endif
-
-// === Special Features
-
-// I2S (steppers & other output-only pins)
-#define USE_I2S_OUT
-#define USE_I2S_STEPS
-//#define DEFAULT_STEPPER ST_I2S_STATIC
-
-#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
-
-#define I2S_OUT_BCK "gpio.22"
-#define I2S_OUT_WS "gpio.17"
-#define I2S_OUT_DATA "gpio.21"
-
-
-#define STEPPER_MS1 "gpio.23" // MOSI
-#define STEPPER_MS2 "gpio.18" // SCK
-
-#define STEPPER_X_MS3 "i2so.3" // X_CS
-#define STEPPER_Y_MS3 "i2so.6" // Y_CS
-#define STEPPER_Z_MS3 "i2so.11" // Z_CS
-#define STEPPER_A_MS3 "i2so.14" // A_CS
-#define STEPPER_B_MS3 "i2so.19" // B_CS
-#define STEPPER_C_MS3 "i2so.22" // C_CS
-
-#define STEPPER_RESET "gpio.19"
-
-#define X_DISABLE_PIN "i2so.0"
-#define X_DIRECTION_PIN "i2so.1"
-#define X_STEP_PIN "i2so.2"
-
-#define X2_DIRECTION_PIN "i2so.4"
-#define X2_STEP_PIN "i2so.5"
-#define X2_DISABLE_PIN "i2so.7"
-
-#define Y_DISABLE_PIN "i2so.8"
-#define Y_DIRECTION_PIN "i2so.9"
-#define Y_STEP_PIN "i2so.10"
-
-#define Y2_DIRECTION_PIN "i2so.12"
-#define Y2_STEP_PIN "i2so.13"
-#define Y2_DISABLE_PIN "i2so.15"
-
-#define Z_DISABLE_PIN "i2so.16"
-#define Z_DIRECTION_PIN "i2so.17"
-#define Z_STEP_PIN "i2so.18"
-
-#define Z2_DIRECTION_PIN "i2so.20"
-#define Z2_STEP_PIN "i2so.21"
-#define Z2_DISABLE_PIN "i2so.23"
-
-
-#define SPINDLE_TYPE SpindleType::PWM // only one spindle at a time
-#define SPINDLE_OUTPUT_PIN "gpio.26"
-#define SPINDLE_ENABLE_PIN "gpio.4"
-#define SPINDLE_DIR_PIN "gpio.16"
-
-#define X_LIMIT_PIN "gpio.36"
-#define Y_LIMIT_PIN "gpio.39"
-#define Z_LIMIT_PIN "gpio.34"
-//#define A_LIMIT_PIN "gpio.35"
-//#define B_LIMIT_PIN "gpio.32"
-//#define C_LIMIT_PIN "gpio.33"
-
-#define PROBE_PIN "gpio.25"
-
-#define COOLANT_MIST_PIN "gpio.2"
-
-// === Default settings
-#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
diff --git a/Grbl_Esp32/src/Machines/i2s_out_xyzabc.h b/Grbl_Esp32/src/Machines/i2s_out_xyzabc.h
deleted file mode 100644
index 867f5e1e..00000000
--- a/Grbl_Esp32/src/Machines/i2s_out_xyzabc.h
+++ /dev/null
@@ -1,105 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- i2s_out_xyzabc.h
- Part of Grbl_ESP32
- Pin assignments for the ESP32 I2S 6-axis board
- 2018 - Bart Dring
- 2020 - Mitch Bradley
- 2020 - Michiyasu Odaki
- 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 .
-*/
-#define MACHINE_NAME "ESP32 I2S 6 Axis Driver Board (StepStick)"
-
-#ifdef N_AXIS
- #undef N_AXIS
-#endif
-#define N_AXIS 6
-
-#ifdef ENABLE_SD_CARD
- #undef ENABLE_SD_CARD
-#endif
-
-// === Special Features
-
-// I2S (steppers & other output-only pins)
-#define USE_I2S_OUT
-#define USE_I2S_STEPS
-//#define DEFAULT_STEPPER ST_I2S_STATIC
-
-#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
-
-#define I2S_OUT_BCK "gpio.22"
-#define I2S_OUT_WS "gpio.17"
-#define I2S_OUT_DATA "gpio.21"
-
-
-#define STEPPER_MS1 "gpio.23" // MOSI
-#define STEPPER_MS2 "gpio.18" // SCK
-
-#define STEPPER_X_MS3 "i2so.3" // X_CS
-#define STEPPER_Y_MS3 "i2so.6" // Y_CS
-#define STEPPER_Z_MS3 "i2so.11" // Z_CS
-#define STEPPER_A_MS3 "i2so.14" // A_CS
-#define STEPPER_B_MS3 "i2so.19" // B_CS
-#define STEPPER_C_MS3 "i2so.22" // C_CS
-
-#define STEPPER_RESET "gpio.19"
-
-#define X_DISABLE_PIN "i2so.0"
-#define X_DIRECTION_PIN "i2so.1"
-#define X_STEP_PIN "i2so.2"
-
-#define Y_DIRECTION_PIN "i2so.4"
-#define Y_STEP_PIN "i2so.5"
-#define Y_DISABLE_PIN "i2so.7"
-
-#define Z_DISABLE_PIN "i2so.8"
-#define Z_DIRECTION_PIN "i2so.9"
-#define Z_STEP_PIN "i2so.10"
-
-#define A_DIRECTION_PIN "i2so.12"
-#define A_STEP_PIN "i2so.13"
-#define A_DISABLE_PIN "i2so.15"
-
-#define B_DISABLE_PIN "i2so.16"
-#define B_DIRECTION_PIN "i2so.17"
-#define B_STEP_PIN "i2so.18"
-//#define B_CS_PIN "i2so.19"
-
-#define C_DIRECTION_PIN "i2so.20"
-#define C_STEP_PIN "i2so.21"
-//#define C_CS_PIN "i2so.22"
-#define C_DISABLE_PIN "i2so.23"
-
-
-#define SPINDLE_TYPE SpindleType::PWM // only one spindle at a time
-#define SPINDLE_OUTPUT_PIN "gpio.26"
-#define SPINDLE_ENABLE_PIN "gpio.4"
-#define SPINDLE_DIR_PIN "gpio.16"
-
-#define X_LIMIT_PIN "gpio.36"
-#define Y_LIMIT_PIN "gpio.39"
-#define Z_LIMIT_PIN "gpio.34"
-#define A_LIMIT_PIN "gpio.35"
-#define B_LIMIT_PIN "gpio.32"
-#define C_LIMIT_PIN "gpio.33"
-
-#define PROBE_PIN "gpio.25"
-
-#define COOLANT_MIST_PIN "gpio.2"
-
-
-
-// === Default settings
-#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
diff --git a/Grbl_Esp32/src/Machines/i2s_out_xyzabc_trinamic.h b/Grbl_Esp32/src/Machines/i2s_out_xyzabc_trinamic.h
deleted file mode 100644
index 0da63d73..00000000
--- a/Grbl_Esp32/src/Machines/i2s_out_xyzabc_trinamic.h
+++ /dev/null
@@ -1,106 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- i2s_out_xyzabc_trinamic.h
- Part of Grbl_ESP32
- Pin assignments for the ESP32 SPI 6-axis board
- 2018 - Bart Dring
- 2020 - Mitch Bradley
- 2020 - Michiyasu Odaki
- 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 .
-*/
-#define MACHINE_NAME "ESP32 SPI 6 Axis Driver Board Trinamic"
-
-#ifdef N_AXIS
- #undef N_AXIS
-#endif
-#define N_AXIS 6
-
-// === Special Features
-
-// I2S (steppers & other output-only pins)
-#define USE_I2S_OUT
-#define USE_I2S_STEPS
-//#define DEFAULT_STEPPER ST_I2S_STATIC
-
-#define I2S_OUT_BCK "gpio.22"
-#define I2S_OUT_WS "gpio.17"
-#define I2S_OUT_DATA "gpio.21"
-
-#define TRINAMIC_RUN_MODE TrinamicMode :: CoolStep
-#define TRINAMIC_HOMING_MODE TrinamicMode :: CoolStep
-
-#define X_TRINAMIC_DRIVER 2130
-#define X_DISABLE_PIN "i2so.0"
-#define X_DIRECTION_PIN "i2so.1"
-#define X_STEP_PIN "i2so.2"
-#define X_CS_PIN "i2so.3"
-#define X_RSENSE TMC2130_RSENSE_DEFAULT
-
-#define Y_TRINAMIC_DRIVER 2130
-#define Y_DIRECTION_PIN "i2so.4"
-#define Y_STEP_PIN "i2so.5"
-#define Y_DISABLE_PIN "i2so.7"
-#define Y_CS_PIN "i2so.6"
-#define Y_RSENSE X_RSENSE
-
-#define Z_TRINAMIC_DRIVER 2130
-#define Z_DISABLE_PIN "i2so.8"
-#define Z_DIRECTION_PIN "i2so.9"
-#define Z_STEP_PIN "i2so.10"
-#define Z_CS_PIN "i2so.11"
-#define Z_RSENSE X_RSENSE
-
-#define A_TRINAMIC_DRIVER 2130
-#define A_DIRECTION_PIN "i2so.12"
-#define A_STEP_PIN "i2so.13"
-#define A_DISABLE_PIN "i2so.15"
-#define A_CS_PIN "i2so.14"
-#define A_RSENSE X_RSENSE
-
-#define B_TRINAMIC_DRIVER 2130
-#define B_DISABLE_PIN "i2so.16"
-#define B_DIRECTION_PIN "i2so.17"
-#define B_STEP_PIN "i2so.18"
-#define B_CS_PIN "i2so.19"
-#define B_RSENSE X_RSENSE
-
-#define C_TRINAMIC_DRIVER 2130
-#define C_DIRECTION_PIN "i2so.20"
-#define C_STEP_PIN "i2so.21"
-#define C_DISABLE_PIN "i2so.23"
-#define C_CS_PIN "i2so.22"
-#define C_RSENSE X_RSENSE
-
-/*
-#define SPINDLE_TYPE SpindleType::PWM // only one spindle at a time
-#define SPINDLE_OUTPUT_PIN "gpio.26"
-#define SPINDLE_ENABLE_PIN "gpio.4"
-#define SPINDLE_DIR_PIN "gpio.16"
-*/
-#define X_LIMIT_PIN "gpio.33"
-#define Y_LIMIT_PIN "gpio.32"
-#define Z_LIMIT_PIN "gpio.35"
-#define A_LIMIT_PIN "gpio.34"
-#define B_LIMIT_PIN "gpio.39"
-#define C_LIMIT_PIN "gpio.36"
-
-#define SPINDLE_TYPE SpindleType::RELAY
-#define SPINDLE_OUTPUT_PIN "gpio.26"
-
-#define PROBE_PIN "gpio.25"
-
-#define COOLANT_MIST_PIN "gpio.2"
-
-// === Default settings
-#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
diff --git a/Grbl_Esp32/src/Machines/midtbot.h b/Grbl_Esp32/src/Machines/midtbot.h
index ab584d4b..1f9bfc70 100644
--- a/Grbl_Esp32/src/Machines/midtbot.h
+++ b/Grbl_Esp32/src/Machines/midtbot.h
@@ -29,11 +29,7 @@
#define CUSTOM_CODE_FILENAME "../Custom/CoreXY.cpp"
-#define MIDTBOT // applies the geometry correction to the kinematics
-#define USE_KINEMATICS // there are kinematic equations for this machine
-#define USE_FWD_KINEMATICS // report in cartesian
-#define USE_MACHINE_INIT // There is some custom initialization for this machine
-#define USE_CUSTOM_HOMING
+#define MIDTBOT // applies the geometry correction to the kinematics
#define SPINDLE_TYPE SpindleType::NONE
@@ -50,8 +46,6 @@
#define Z_SERVO_PIN "gpio.27"
-// Set $Homing/Cycle0=Y and $Homing/Cycle1=X
-
#define SPINDLE_TYPE SpindleType::NONE
// defaults
diff --git a/Grbl_Esp32/src/Machines/mpcnc_laser_module_v1p2.h b/Grbl_Esp32/src/Machines/mpcnc_laser_module_v1p2.h
index e45c658d..257db30e 100644
--- a/Grbl_Esp32/src/Machines/mpcnc_laser_module_v1p2.h
+++ b/Grbl_Esp32/src/Machines/mpcnc_laser_module_v1p2.h
@@ -30,7 +30,6 @@
#define MACHINE_NAME "MPCNC_V1P2 with Laser Module"
// The laser module fires without a low signal. This keeps the enable on
-#define USE_MACHINE_INIT
#define LVL_SHIFT_ENABLE "gpio.32"
#define CUSTOM_CODE_FILENAME "Custom/mpcnc_laser_module.cpp"
@@ -53,8 +52,8 @@
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN "gpio.13"
-#define SPINDLE_TYPE SpindleType::PWM
-#define SPINDLE_OUTPUT_PIN "gpio.16"
+#define SPINDLE_TYPE SpindleType::Laser
+#define LASER_OUTPUT_PIN "gpio.16"
#define COOLANT_MIST_PIN "gpio.2"
diff --git a/Grbl_Esp32/src/Machines/polar_coaster.h b/Grbl_Esp32/src/Machines/polar_coaster.h
index 0b6571ef..c367b36f 100644
--- a/Grbl_Esp32/src/Machines/polar_coaster.h
+++ b/Grbl_Esp32/src/Machines/polar_coaster.h
@@ -37,9 +37,6 @@
#define POLAR_AXIS 1
#define SEGMENT_LENGTH 0.5 // segment length in mm
-#define USE_KINEMATICS
-#define USE_FWD_KINEMATICS // report in cartesian
-#define USE_M30
#define X_STEP_PIN "gpio.15"
#define Y_STEP_PIN "gpio.2"
@@ -123,4 +120,6 @@
#define DEFAULT_X_MAX_TRAVEL 50.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
-#define DEFAULT_Z_MAX_TRAVEL 100.0 // This is percent in servo mode
+#define DEFAULT_Z_MAX_TRAVEL 5.0 // This is percent in servo mode
+
+#define DEFAULT_Z_HOMING_MPOS DEFAULT_Z_MAX_TRAVEL // stays up after homing
diff --git a/Grbl_Esp32/src/Machines/spi_daisy_4axis_xyz.h b/Grbl_Esp32/src/Machines/spi_daisy_4axis_xyz.h
deleted file mode 100644
index fcac8899..00000000
--- a/Grbl_Esp32/src/Machines/spi_daisy_4axis_xyz.h
+++ /dev/null
@@ -1,84 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- spi_daisy_4axis_xyz.h
- Part of Grbl_ESP32
-
- Pin assignments for a 4-axis machine using Triaminic drivers
- in daisy-chained SPI mode.
- https://github.com/bdring/4_Axis_SPI_CNC
-
- 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 .
-*/
-
-#define MACHINE_NAME "SPI_DAISY_4X_XYZ"
-
-#ifdef N_AXIS
- #undef N_AXIS
-#endif
-#define N_AXIS 3
-
-#define TRINAMIC_DAISY_CHAIN
-
-#define TRINAMIC_RUN_MODE TrinamicMode :: CoolStep
-#define TRINAMIC_HOMING_MODE TrinamicMode :: CoolStep
-
-// Use SPI enable instead of the enable pin
-// The hardware enable pin is tied to ground
-#define USE_TRINAMIC_ENABLE
-
-#define X_TRINAMIC_DRIVER 2130 // Which Driver Type?
-#define X_RSENSE TMC2130_RSENSE_DEFAULT
-#define X_STEP_PIN "gpio.12"
-#define X_DIRECTION_PIN "gpio.14"
-#define X_CS_PIN "gpio.17" // Daisy Chain, all share same CS pin
-
-#define Y_TRINAMIC_DRIVER 2130 // Which Driver Type?
-#define Y_RSENSE TMC2130_RSENSE_DEFAULT
-#define Y_STEP_PIN "gpio.27"
-#define Y_DIRECTION_PIN "gpio.26"
-#define Y_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
-
-#define Z_TRINAMIC_DRIVER 2130 // Which Driver Type?
-#define Z_RSENSE TMC2130_RSENSE_DEFAULT
-#define Z_STEP_PIN "gpio.15"
-#define Z_DIRECTION_PIN "gpio.2"
-#define Z_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin
-
-
-// Mist is a 3.3V output
-// Turn on with M7 and off with M9
-#define COOLANT_MIST_PIN "gpio.21"
-
-#define SPINDLE_TYPE SpindleType::PWM
-#define SPINDLE_OUTPUT_PIN "gpio.25"
-#define SPINDLE_ENABLE_PIN "gpio.4"
-
-// Relay operation
-// Install Jumper near relay
-// For spindle Use max RPM of 1
-// For PWM remove jumper and set MAX RPM to something higher ($30 setting)
-// Interlock jumper along top edge needs to be installed for both versions
-#define DEFAULT_SPINDLE_RPM_MAX 1 // Should be 1 for relay operation
-
-#define PROBE_PIN "gpio.22"
-
-#define X_LIMIT_PIN "gpio.36"
-#define Y_LIMIT_PIN "gpio.39"
-#define Z_LIMIT_PIN "gpio.34"
-
diff --git a/Grbl_Esp32/src/Machines/tapster_3.h b/Grbl_Esp32/src/Machines/tapster_3.h
index 0eb185af..cbd23550 100644
--- a/Grbl_Esp32/src/Machines/tapster_3.h
+++ b/Grbl_Esp32/src/Machines/tapster_3.h
@@ -23,12 +23,6 @@
#define N_AXIS 3
-// ================= Firmware Customization ===================
-
-#define USE_KINEMATICS // there are kinematic equations for this machine
-#define USE_FWD_KINEMATICS // report in cartesian
-#define USE_MACHINE_INIT // There is some custom initialization for this machine
-
// ================== Delta Geometry ===========================
#define RADIUS_FIXED 70.0 // radius of the fixed side (length of motor cranks)
diff --git a/Grbl_Esp32/src/Machines/tapster_pro_6P_trinamic.h b/Grbl_Esp32/src/Machines/tapster_pro_6P_trinamic.h
index 09597403..66d5092d 100644
--- a/Grbl_Esp32/src/Machines/tapster_pro_6P_trinamic.h
+++ b/Grbl_Esp32/src/Machines/tapster_pro_6P_trinamic.h
@@ -26,8 +26,6 @@
#define FWD_KINEMATICS_REPORTING // report in cartesian
#define USE_RMT_STEPS // Use the RMT periferal to generate step pulses
#define USE_TRINAMIC // some Trinamic motors are used on this machine
-#define USE_MACHINE_TRINAMIC_INIT // there is a machine specific setup for the drivers
-#define USE_MACHINE_INIT // There is some custom initialization for this machine
#define SEGMENT_LENGTH 0.5 // segment length in mm
#define KIN_ANGLE_CALC_OK 0
@@ -41,10 +39,6 @@
#define N_AXIS 3
-#define USE_KINEMATICS // there are kinematic equations for this machine
-#define USE_FWD_KINEMATICS // report in cartesian
-#define USE_MACHINE_INIT // There is some custom initialization for this machine
-
// ================== Delta Geometry ===========================
#define RADIUS_FIXED 100.0f // radius of the fixed side (length of motor cranks)
diff --git a/Grbl_Esp32/src/Machines/template.h b/Grbl_Esp32/src/Machines/template.h
deleted file mode 100644
index 60367c1d..00000000
--- a/Grbl_Esp32/src/Machines/template.h
+++ /dev/null
@@ -1,233 +0,0 @@
-#pragma once
-// clang-format off
-
-/*
- template.h
- Part of Grbl_ESP32
-
- Template for a machine configuration file.
-
- 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 .
-*/
-
-// This contains a long list of things that might possibly be
-// configured. Most machines - especially simple cartesian machines
-// that use stepper motors - will only need to define a few of the
-// options herein, often just the pin assignments.
-
-// Pin assignments depend on how the ESP32 is connected to
-// the external machine. Typically the ESP32 module plugs into
-// an adapter board that wires specific ESP32 GPIO pins to
-// other connectors on the board, such as Pololu sockets for
-// stepper drivers or connectors for external drivers, limit
-// pins, spindle control, etc. This file describes how those
-// GPIO pins are wired to those other connectors.
-
-// Some machines might choose to use an adapter board in a
-// non-standard way, for example a 3-axis board might have axes
-// labeled XYZ, but the machine might have only 2 axes one of which is
-// driven by two ganged motors. In that case, you would need
-// a custom version of this file that assigns the pins differently
-// from the adapter board labels.
-
-// In addition to pin assignments, many other aspects of Grbl
-// can be configured, such as spindle speeds, special motor
-// types like servos and unipolars, homing order, default values
-// for $$ settings, etc. A detailed list of such options is
-// given below.
-
-// Furthermore, it is possible to implement special complex
-// behavior in custom C++ code, for non-Cartesian machines,
-// unusual homing cycles, etc. See the Special Features section
-// below for additional instructions.
-
-// === Machine Name
-// Change TEMPLATE to some name of your own choosing. That name
-// will be shown in a Grbl startup message to identify your
-// configuration.
-
-#define MACHINE_NAME "TEMPLATE"
-
-// If your machine requires custom code as described below in
-// Special Features, you must copy Custom/custom_code_template.cpp
-// to a new name like Custom/my_custom_code.cpp, implement the
-// functions therein, and enable its use by defining:
-// #define CUSTOM_CODE_FILENAME "Custom/my_custom_code.cpp"
-
-// === Number of axes
-
-// You can set the number of axes that the machine supports
-// by defining N_AXIS. If you do not define it, 3 will be
-// used. The value must be at least 3, even if your machine
-// has fewer axes.
-// #define N_AXIS 4
-
-
-// == Pin Assignments
-
-// Step and direction pins; these must be output-capable pins,
-// specifically ESP32 GPIO numbers 0..31
-// #define X_STEP_PIN "gpio.12"
-// #define X_DIRECTION_PIN "gpio.14"
-// #define Y_STEP_PIN "gpio.26"
-// #define Y_DIRECTION_PIN "gpio.15"
-// #define Z_STEP_PIN "gpio.27"
-// #define Z_DIRECTION_PIN "gpio.33"
-
-// #define X_LIMIT_PIN "gpio.17"
-// #define Y_LIMIT_PIN "gpio.4"
-// #define Z_LIMIT_PIN "gpio.16"
-
-// Common enable for all steppers. If it is okay to leave
-// your drivers enabled at all times, you can leave
-// STEPPERS_DISABLE_PIN undefined and use the pin for something else.
-// #define STEPPERS_DISABLE_PIN "gpio.13"
-
-// Pins for controlling various aspects of the machine. If your
-// machine does not support one of these features, you can leave
-// the corresponding pin undefined.
-
-// #define SPINDLE_OUTPUT_PIN "gpio.2" // labeled SpinPWM
-// #define SPINDLE_ENABLE_PIN "gpio.22" // labeled SpinEnbl
-// #define COOLANT_MIST_PIN "gpio.21" // labeled Mist
-// #define COOLANT_FLOOD_PIN "gpio.25" // labeled Flood
-// #define PROBE_PIN "gpio.32" // labeled Probe
-
-// Input pins for various functions. If the corresponding pin is not defined,
-// the function will not be available.
-
-// CONTROL_SAFETY_DOOR_PIN shuts off the machine when a door is opened
-// or some other unsafe condition exists.
-// #define CONTROL_SAFETY_DOOR_PIN "gpio.35" // labeled Door, needs external pullup
-
-// RESET, FEED_HOLD, and CYCLE_START can control GCode execution at
-// the push of a button.
-
-// #define CONTROL_RESET_PIN "gpio.34" // labeled Reset, needs external pullup
-// #define CONTROL_FEED_HOLD_PIN "gpio.36" // labeled Hold, needs external pullup
-// #define CONTROL_CYCLE_START_PIN "gpio.39" // labeled Start, needs external pullup
-
-// === Ganging
-// If you need to use two motors on one axis, you can "gang" the motors by
-// defining a second pin to control the other motor on the axis. For example:
-
-// #define Y2_STEP_PIN "gpio.27" /* labeled Z */
-// #define Y2_DIRECTION_PIN "gpio.33" /* labeled Z */
-
-// === Servos
-// To use a servo motor on an axis, do not define step and direction
-// pins for that axis, but instead include a block like this:
-
-// #define SERVO_Z_PIN "gpio.22"
-
-// === Homing cycles
-// Set them using $Homing/Cycle0= optionally up to $Homing/Cycle5=
-
-// === Default settings
-// Grbl has many run-time settings that the user can changed by
-// commands like $110=2000 . Their values are stored in non-volatile
-// storage so they persist after the controller has been powered down.
-// Those settings have default values that are used if the user
-// has not altered them, or if the settings are explicitly reset
-// to the default values wth $RST=$.
-//
-// The default values are established in defaults.h, but you
-// can override any one of them by definining it here, for example:
-
-//#define DEFAULT_INVERT_LIMIT_PINS 1
-//#define DEFAULT_REPORT_INCHES 1
-
-// === Control Pins
-
-// If some of the control pin switches are normally closed
-// (the default is normally open), you can invert some of them
-// with INVERT_CONTROL_PIN_MASK. The bits in the mask are
-// Cycle Start, Feed Hold, Reset, Safety Door. To use a
-// normally open switch on Reset, you would say
-// #define INVERT_CONTROL_PIN_MASK B1101
-
-// If your control pins do not have adequate hardware signal
-// conditioning, you can define these to use software to
-// reduce false triggering.
-// #define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
-// #define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
-
-
-// Grbl_ESP32 use the ESP32's special RMT (IR remote control) hardware
-// engine to achieve more precise high step rates than can be done
-// in software. That feature is enabled by default, but there are
-// some machines that might not want to use it, such as machines that
-// do not use ordinary stepper motors. To turn it off, do this:
-// #undef USE_RMT_STEPS
-
-// === Special Features
-// Grbl_ESP32 can support non-Cartesian machines and some other
-// scenarios that cannot be handled by choosing from a set of
-// predefined selections. Instead they require machine-specific
-// C++ code functions. There are callouts in the core code for
-// such code, guarded by ifdefs that enable calling the individual
-// functions. custom_code_template.cpp describes the functions
-// that you can implement. The ifdef guards are described below:
-//
-// USE_CUSTOM_HOMING enables the user_defined_homing(uint8_t cycle_mask) function
-// that can implement an arbitrary homing sequence.
-// #define USE_CUSTOM_HOMING
-
-// USE_KINEMATICS enables the functions inverse_kinematics(),
-// kinematics_pre_homing(), and kinematics_post_homing(),
-// so non-Cartesian machines can be implemented.
-// #define USE_KINEMATICS
-
-// USE_FWD_KINEMATICS enables the forward_kinematics() function
-// that converts motor positions in non-Cartesian coordinate
-// systems back to Cartesian form, for status reports.
-//#define USE_FWD_KINEMATICS
-
-// USE_TOOL_CHANGE enables the user_tool_change() function
-// that implements custom tool change procedures.
-// #define USE_TOOL_CHANGE
-
-// Any one of MACRO_BUTTON_0_PIN, MACRO_BUTTON_1_PIN, and MACRO_BUTTON_2_PIN
-// enables the user_defined_macro(number) function which
-// implements custom behavior at the press of a button
-// #define MACRO_BUTTON_0_PIN
-
-// USE_M30 enables the user_m30() function which implements
-// custom behavior when a GCode programs stops at the end
-// #define USE_M30
-
-// USE_TRIAMINIC enables a suite of functions that are defined
-// in grbl_triaminic.cpp, allowing the use of Triaminic stepper
-// drivers that require software configuration at startup.
-// There are several options that control the details of such
-// drivers; inspect the code in grbl_triaminic.cpp to see them.
-// #define USE_TRIAMINIC
-// #define X_TRIAMINIC
-// #define X_DRIVER_TMC2209
-// #define TRIAMINIC_DAISY_CHAIN
-
-// USE_MACHINE_TRINAMIC_INIT enables the machine_triaminic_setup()
-// function that replaces the normal setup of Triaminic drivers.
-// It could, for, example, setup StallGuard or other special modes.
-// #define USE_MACHINE_TRINAMIC_INIT
-
-
-// === Grbl behavior options
-// There are quite a few options that control aspects of Grbl that
-// are not specific to particular machines. They are listed and
-// described in config.h after it includes the file machine.h.
-// Normally you would not need to change them, but if you do,
-// it will be necessary to make the change in config.h
diff --git a/Grbl_Esp32/src/MotionControl.cpp b/Grbl_Esp32/src/MotionControl.cpp
index c7ba7f52..c9d416c4 100644
--- a/Grbl_Esp32/src/MotionControl.cpp
+++ b/Grbl_Esp32/src/MotionControl.cpp
@@ -5,8 +5,8 @@
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
Copyright (c) 2009-2011 Simen Svale Skogsrud
- 2018 - Bart Dring This file was modifed for use on the ESP32
- CPU. Do not use this with Grbl for atMega328P
+ 2018 - Bart Dring This file was modifed for use on the ESP32
+ CPU. Do not use this with Grbl for atMega328P
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
@@ -34,15 +34,6 @@
SquaringMode ganged_mode = SquaringMode::Dual;
-// this allows kinematics to be used.
-void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position) {
-#ifndef USE_KINEMATICS
- mc_line(target, pl_data);
-#else // else use kinematics
- inverse_kinematics(target, pl_data, position);
-#endif
-}
-
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
// (1 minute)/feed_rate time.
@@ -50,7 +41,12 @@ void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position) {
// segments, must pass through this routine before being passed to the planner. The seperation of
// mc_line and plan_buffer_line is done primarily to place non-planner-type functions from being
// in the planner and to let backlash compensation or canned cycle integration simple and direct.
-void mc_line(float* target, plan_line_data_t* pl_data) {
+// returns true if line was submitted to planner, or false if intentionally dropped.
+bool mc_line(float* target, plan_line_data_t* pl_data) {
+ bool submitted_result = false;
+ // store the plan data so it can be cancelled by the protocol system if needed
+ sys_pl_data_inflight = pl_data;
+
// If enabled, check for soft limit violations. Placed here all line motions are picked up
// from everywhere in Grbl.
if (soft_limits->get()) {
@@ -61,7 +57,8 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
}
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
if (sys.state == State::CheckMode) {
- return;
+ sys_pl_data_inflight = NULL;
+ return submitted_result; // Bail, if system abort.
}
// NOTE: Backlash compensation may be installed here. It will need direction info to track when
// to insert a backlash line motion(s) before the intended line motion and will require its own
@@ -81,7 +78,8 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
do {
protocol_execute_realtime(); // Check for any run-time commands
if (sys.abort) {
- return; // Bail, if system abort.
+ sys_pl_data_inflight = NULL;
+ return submitted_result; // Bail, if system abort.
}
if (plan_check_full_buffer()) {
protocol_auto_cycle_start(); // Auto-cycle start when buffer is full.
@@ -91,9 +89,29 @@ void mc_line(float* target, plan_line_data_t* pl_data) {
} while (1);
// Plan and queue motion into planner buffer
// uint8_t plan_status; // Not used in normal operation.
- plan_buffer_line(target, pl_data);
+ if (sys_pl_data_inflight == pl_data) {
+ plan_buffer_line(target, pl_data);
+ submitted_result = true;
+ }
+ sys_pl_data_inflight = NULL;
+ return submitted_result;
}
+bool __attribute__((weak)) cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
+ return mc_line(target, pl_data);
+}
+
+bool __attribute__((weak)) kinematics_pre_homing(uint8_t cycle_mask) {
+ return false; // finish normal homing cycle
+}
+
+void __attribute__((weak)) kinematics_post_homing() {}
+
+void __attribute__((weak)) motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
+ memcpy(cartesian, motors, n_axis * sizeof(motors[0]));
+}
+
+void __attribute__((weak)) forward_kinematics(float* position) {}
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used
@@ -118,14 +136,13 @@ void mc_arc(float* target,
float rt_axis1 = target[axis_1] - center_axis1;
float previous_position[MAX_N_AXIS] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
-#ifdef USE_KINEMATICS
uint16_t n;
auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
for (n = 0; n < n_axis; n++) {
previous_position[n] = position[n];
}
-#endif
+
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
float angular_travel = atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1);
if (is_clockwise_arc) { // Correct atan2 output per direction
@@ -185,8 +202,9 @@ void mc_arc(float* target,
float cos_Ti;
float r_axisi;
uint16_t i;
- uint8_t count = 0;
- for (i = 1; i < segments; i++) { // Increment (segments-1).
+ uint8_t count = 0;
+ float original_feedrate = pl_data->feed_rate; // Kinematics may alter the feedrate, so save an original copy
+ for (i = 1; i < segments; i++) { // Increment (segments-1).
if (count < N_ARC_CORRECTION) {
// Apply vector rotation matrix. ~40 usec
r_axisi = r_axis0 * sin_T + r_axis1 * cos_T;
@@ -206,14 +224,11 @@ void mc_arc(float* target,
position[axis_0] = center_axis0 + r_axis0;
position[axis_1] = center_axis1 + r_axis1;
position[axis_linear] += linear_per_segment;
-#ifdef USE_KINEMATICS
- mc_line_kins(position, pl_data, previous_position);
+ pl_data->feed_rate = original_feedrate; // This restores the feedrate kinematics may have altered
+ cartesian_to_motors(position, pl_data, previous_position);
previous_position[axis_0] = position[axis_0];
previous_position[axis_1] = position[axis_1];
previous_position[axis_linear] = position[axis_linear];
-#else
- mc_line(position, pl_data);
-#endif
// Bail mid-circle on system abort. Runtime command check already performed by mc_line.
if (sys.abort) {
return;
@@ -221,16 +236,16 @@ void mc_arc(float* target,
}
}
// Ensure last segment arrives at target location.
- mc_line_kins(target, pl_data, previous_position);
+ cartesian_to_motors(target, pl_data, previous_position);
}
// Execute dwell in seconds.
-void mc_dwell(float seconds) {
- if (sys.state == State::CheckMode) {
- return;
+bool mc_dwell(int32_t milliseconds) {
+ if (milliseconds <= 0 || sys.state == State::CheckMode) {
+ return false;
}
protocol_buffer_synchronize();
- delay_sec(seconds, DELAY_MODE_DWELL);
+ return delay_msec(milliseconds, DwellMode::Dwell);
}
// return true if the mask has exactly one bit set,
@@ -247,16 +262,17 @@ static bool mask_is_single_axis(uint8_t axis_mask) {
return axis_mask && ((axis_mask & (axis_mask - 1)) == 0);
}
-// return true if the axis is defined as a squared axis
-// Squaring: is used on gantry type axes that have two motors
-// Each motor with touch off its own switch to square the axis
-static bool mask_has_squared_axis(uint8_t axis_mask) {
- return axis_mask & homing_squared_axes->get();
-}
-
-// return true if axis_mask refers to a single squared axis
static bool axis_is_squared(uint8_t axis_mask) {
- return mask_is_single_axis(axis_mask) && mask_has_squared_axis(axis_mask);
+ // Squaring can only be done if it is the only axis in the mask
+ if (axis_mask & homing_squared_axes->get()) {
+ if (mask_is_single_axis(axis_mask)) {
+ return true;
+ }
+ grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Cannot multi-axis home with squared axes. Homing normally");
+ return false;
+ }
+
+ return false;
}
#ifdef USE_I2S_STEPS
@@ -283,18 +299,16 @@ static bool axis_is_squared(uint8_t axis_mask) {
// executing the homing cycle. This prevents incorrect buffered plans after homing.
void mc_homing_cycle(uint8_t cycle_mask) {
bool no_cycles_defined = true;
-#ifdef USE_CUSTOM_HOMING
+
if (user_defined_homing(cycle_mask)) {
return;
}
-#endif
+
// This give kinematics a chance to do something before normal homing
// if it returns true, the homing is canceled.
-#ifdef USE_KINEMATICS
if (kinematics_pre_homing(cycle_mask)) {
return;
}
-#endif
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
// with machines with limits wired on both ends of travel to one limit pin.
// TODO: Move the pin-specific LIMIT_PIN call to Limits.cpp as a function.
@@ -364,10 +378,8 @@ void mc_homing_cycle(uint8_t cycle_mask) {
// Sync gcode parser and planner positions to homed position.
gc_sync_position();
plan_sync_position();
-#ifdef USE_KINEMATICS
// This give kinematics a chance to do something after normal homing
kinematics_post_homing();
-#endif
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
limits_init();
}
@@ -438,7 +450,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
}
sys_probe_state = ProbeState::Off; // Ensure probe state monitor is disabled.
- protocol_execute_realtime(); // Check and execute run-time commands
+ protocol_execute_realtime(); // Check and execute run-time commands
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
st_reset(); // Reset step segment buffer.
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
@@ -497,6 +509,7 @@ void mc_override_ctrl_update(uint8_t override_state) {
// lost, since there was an abrupt uncontrolled deceleration. Called at an interrupt level by
// realtime abort command and hard limits. So, keep to a minimum.
void mc_reset() {
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Debug, "mc_reset()");
// Only this function can set the system reset. Helps prevent multiple kill calls.
if (!sys_rt_exec_state.bit.reset) {
sys_rt_exec_state.bit.reset = true;
@@ -506,11 +519,11 @@ void mc_reset() {
MachineConfig::instance()->_coolant->stop();
// turn off all User I/O immediately
- sys_io_control(0xFF, LOW, false);
- sys_pwm_control(0xFF, 0, false);
+ sys_digital_all_off();
+ sys_analog_all_off();
#ifdef ENABLE_SD_CARD
// do we need to stop a running SD job?
- if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
+ if (get_sd_state(false) == SDState::BusyPrinting) {
//Report print stopped
report_feedback_message(Message::SdFileQuit);
closeFile();
diff --git a/Grbl_Esp32/src/MotionControl.h b/Grbl_Esp32/src/MotionControl.h
index c9177f0b..c9f26c04 100644
--- a/Grbl_Esp32/src/MotionControl.h
+++ b/Grbl_Esp32/src/MotionControl.h
@@ -35,8 +35,8 @@ const int PARKING_MOTION_LINE_NUMBER = 0;
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
// (1 minute)/feed_rate time.
-void mc_line_kins(float* target, plan_line_data_t* pl_data, float* position);
-void mc_line(float* target, plan_line_data_t* pl_data);
+bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position);
+bool mc_line(float* target, plan_line_data_t* pl_data); // returns true if line was submitted to planner
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
@@ -53,7 +53,7 @@ void mc_arc(float* target,
uint8_t is_clockwise_arc);
// Dwell for a specific number of seconds
-void mc_dwell(float seconds);
+bool mc_dwell(int32_t milliseconds);
// Perform homing cycle to locate machine zero. Requires limit switches.
void mc_homing_cycle(uint8_t cycle_mask);
diff --git a/Grbl_Esp32/src/Motors/Dynamixel2.cpp b/Grbl_Esp32/src/Motors/Dynamixel2.cpp
index 3f5c5aa5..c14fee82 100644
--- a/Grbl_Esp32/src/Motors/Dynamixel2.cpp
+++ b/Grbl_Esp32/src/Motors/Dynamixel2.cpp
@@ -32,7 +32,7 @@ namespace Motors {
uint8_t Motors::Dynamixel2::ids[MAX_N_AXIS][2] = { { 0, 0 }, { 0, 0 }, { 0, 0 }, { 0, 0 }, { 0, 0 }, { 0, 0 } };
void Dynamixel2::init() {
- _has_errors = false; // let's start with the assumption we're good.
+ _has_errors = false; // let's start with the assumption we're good.
_axis_index = axis_index();
init_uart(_id, axis_index(), dual_axis_index()); // static and only allows one init
@@ -197,10 +197,9 @@ namespace Motors {
if (_has_errors) {
return false;
}
-
- auto axis = MachineConfig::instance()->_axes->_axis[_axis_index];
- sys_position[_axis_index] =
- axis->_homing->_mpos * axis->_stepsPerMm; // convert to steps
+
+ auto axis = MachineConfig::instance()->_axes->_axis[_axis_index];
+ sys_position[_axis_index] = axis->_homing->_mpos * axis->_stepsPerMm; // convert to steps
set_disable(false);
set_location(); // force the PWM to update now
@@ -354,16 +353,14 @@ namespace Motors {
tx_message[++msg_index] = 4; // low order data length
tx_message[++msg_index] = 0; // high order data length
- auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
+ auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
+ float* mpos = system_get_mpos();
for (uint8_t axis = X_AXIS; axis < n_axis; axis++) {
for (uint8_t gang_index = 0; gang_index < 2; gang_index++) {
current_id = ids[axis][gang_index];
if (current_id != 0) {
count++; // keep track of the count for the message length
- //determine the location of the axis
- float target = system_convert_axis_steps_to_mpos(sys_position, axis); // get the axis machine position in mm
-
dxl_count_min = DXL_COUNT_MIN;
dxl_count_max = DXL_COUNT_MAX;
@@ -373,7 +370,7 @@ namespace Motors {
// map the mm range to the servo range
dxl_position =
- (uint32_t)mapConstrain(target, limitsMinPosition(axis), limitsMaxPosition(axis), dxl_count_min, dxl_count_max);
+ +(uint32_t)mapConstrain(mpos[axis], limitsMinPosition(axis), limitsMaxPosition(axis), dxl_count_min, dxl_count_max);
tx_message[++msg_index] = current_id; // ID of the servo
tx_message[++msg_index] = dxl_position & 0xFF; // data
@@ -452,9 +449,7 @@ namespace Motors {
}
// Configuration registration
- namespace
- {
+ namespace {
MotorFactory::InstanceBuilder registration("dynamixel2");
}
}
-
diff --git a/Grbl_Esp32/src/Motors/Motor.cpp b/Grbl_Esp32/src/Motors/Motor.cpp
index c7e5f7ba..2bc8b678 100644
--- a/Grbl_Esp32/src/Motors/Motor.cpp
+++ b/Grbl_Esp32/src/Motors/Motor.cpp
@@ -16,7 +16,6 @@
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
- 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
Testing
@@ -36,17 +35,18 @@
namespace Motors {
void Motor::debug_message() {}
+ Motor::Motor(uint8_t axis_index) : _axis_index(axis_index % MAX_AXES), _dual_axis_index(axis_index / MAX_AXES) {}
bool Motor::test() { return true; }; // true = OK
uint8_t Motor::axis_index() const {
- Assert(MachineConfig::instance() != nullptr &&
- MachineConfig::instance()->_axes != nullptr, "Expected machine to be configured before this is called.");
+ Assert(MachineConfig::instance() != nullptr && MachineConfig::instance()->_axes != nullptr,
+ "Expected machine to be configured before this is called.");
return MachineConfig::instance()->_axes->findAxisIndex(this);
}
uint8_t Motor::dual_axis_index() const {
- Assert(MachineConfig::instance() != nullptr &&
- MachineConfig::instance()->_axes != nullptr, "Expected machine to be configured before this is called.");
+ Assert(MachineConfig::instance() != nullptr && MachineConfig::instance()->_axes != nullptr,
+ "Expected machine to be configured before this is called.");
return MachineConfig::instance()->_axes->findAxisGanged(this);
}
diff --git a/Grbl_Esp32/src/Motors/RcServo.cpp b/Grbl_Esp32/src/Motors/RcServo.cpp
index 34cb6e04..2c273b2f 100644
--- a/Grbl_Esp32/src/Motors/RcServo.cpp
+++ b/Grbl_Esp32/src/Motors/RcServo.cpp
@@ -39,12 +39,26 @@ namespace Motors {
auto pwmNative = _pwm_pin.getNative(Pin::Capabilities::PWM);
+#ifdef LATER
+ char* setting_cal_min = (char*)malloc(20);
+ sprintf(setting_cal_min, "%c/RcServo/Cal/Min", report_get_axis_letter(_axis_index)); //
+ rc_servo_cal_min = new FloatSetting(EXTENDED, WG, NULL, setting_cal_min, 1.0, 0.5, 2.0);
+
+ char* setting_cal_max = (char*)malloc(20);
+ sprintf(setting_cal_max, "%c/RcServo/Cal/Max", report_get_axis_letter(_axis_index)); //
+ rc_servo_cal_max = new FloatSetting(EXTENDED, WG, NULL, setting_cal_max, 1.0, 0.5, 2.0);
+
+ rc_servo_cal_min->load();
+ rc_servo_cal_max->load();
+#endif
+
read_settings();
_channel_num = sys_get_next_PWM_chan_num();
ledcSetup(_channel_num, SERVO_PULSE_FREQ, SERVO_PULSE_RES_BITS);
ledcAttachPin(pwmNative, _channel_num);
_current_pwm_duty = 0;
+ _disabled = true;
config_message();
startUpdateTask();
}
@@ -72,10 +86,6 @@ namespace Motors {
// sets the PWM to zero. This allows most servos to be manually moved
void RcServo::set_disable(bool disable) {
- if (_disabled == disable) {
- return;
- }
-
_disabled = disable;
if (_disabled) {
_write_pwm(0);
@@ -102,11 +112,6 @@ namespace Motors {
return;
}
- if (sys.state == State::Alarm) {
- set_disable(true);
- return;
- }
-
read_settings();
mpos = system_convert_axis_steps_to_mpos(sys_position, _axis_index); // get the axis machine position in mm
@@ -122,11 +127,14 @@ namespace Motors {
}
void RcServo::read_settings() {
- _pwm_pulse_min = SERVO_MIN_PULSE * _cal_min;
- _pwm_pulse_max = SERVO_MAX_PULSE * _cal_max;
+ if (bitnum_istrue(dir_invert_mask->get(), _axis_index)) {
+ // swap the pwm values
+ _pwm_pulse_min = SERVO_MAX_PULSE * (1.0 + (1.0 - rc_servo_cal_min->get()));
+ _pwm_pulse_max = SERVO_MIN_PULSE * (1.0 + (1.0 - rc_servo_cal_max->get()));
- if (bitnum_istrue(dir_invert_mask->get(), _axis_index)) { // normal direction
- swap(_pwm_pulse_min, _pwm_pulse_max);
+ } else {
+ _pwm_pulse_min = SERVO_MIN_PULSE * rc_servo_cal_min->get();
+ _pwm_pulse_max = SERVO_MAX_PULSE * rc_servo_cal_max->get();
}
}
diff --git a/Grbl_Esp32/src/Motors/Servo.cpp b/Grbl_Esp32/src/Motors/Servo.cpp
index 233d3206..5358a543 100644
--- a/Grbl_Esp32/src/Motors/Servo.cpp
+++ b/Grbl_Esp32/src/Motors/Servo.cpp
@@ -41,6 +41,7 @@ namespace Motors {
}
void Servo::startUpdateTask() {
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Servo Update Task Started");
if (this == List) {
xTaskCreatePinnedToCore(updateTask, // task
"servoUpdateTask", // name for task
@@ -48,7 +49,7 @@ namespace Motors {
NULL, // parameters
1, // priority
NULL, // handle
- 0 // core
+ SUPPORT_TASK_CORE // core
);
}
}
@@ -68,7 +69,9 @@ namespace Motors {
vTaskDelayUntil(&xLastWakeTime, xUpdate);
static UBaseType_t uxHighWaterMark = 0;
+#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
+#endif
}
}
}
diff --git a/Grbl_Esp32/src/Motors/StandardStepper.cpp b/Grbl_Esp32/src/Motors/StandardStepper.cpp
index aa618fab..afc0865c 100644
--- a/Grbl_Esp32/src/Motors/StandardStepper.cpp
+++ b/Grbl_Esp32/src/Motors/StandardStepper.cpp
@@ -40,12 +40,13 @@ namespace Motors {
}
void StandardStepper::init() {
- init_step_dir_pins();
+ read_settings();
config_message();
}
+ void StandardStepper::read_settings() { init_step_dir_pins(); }
void StandardStepper::init_step_dir_pins() {
- auto axisIndex = axis_index();
+ auto axisIndex = axis_index();
_invert_step_pin = bitnum_istrue(step_invert_mask->get(), axisIndex);
_invert_dir_pin = bitnum_istrue(dir_invert_mask->get(), axisIndex);
_dir_pin.setAttr(Pin::Attr::Output);
@@ -61,11 +62,8 @@ namespace Motors {
rmtConfig.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW;
rmtConfig.tx_config.idle_output_en = true;
-# ifdef STEP_PULSE_DELAY
- rmtItem[0].duration0 = STEP_PULSE_DELAY * 4;
-# else
- rmtItem[0].duration0 = 1;
-# endif
+ auto stepPulseDelay = direction_delay_microseconds->get();
+ rmtItem[0].duration0 = stepPulseDelay < 1 ? 1 : stepPulseDelay * 4;
rmtItem[0].duration1 = 4 * pulse_microseconds->get();
rmtItem[1].duration0 = 0;
@@ -125,8 +123,7 @@ namespace Motors {
void StandardStepper::set_disable(bool disable) { _disable_pin.write(disable); }
// Configuration registration
- namespace
- {
+ namespace {
MotorFactory::InstanceBuilder registration("standard_stepper");
}
}
diff --git a/Grbl_Esp32/src/Motors/StandardStepper.h b/Grbl_Esp32/src/Motors/StandardStepper.h
index ae0a9fa5..edb06a1b 100644
--- a/Grbl_Esp32/src/Motors/StandardStepper.h
+++ b/Grbl_Esp32/src/Motors/StandardStepper.h
@@ -18,6 +18,7 @@ namespace Motors {
void set_direction(bool) override;
void step() override;
void unstep() override;
+ void read_settings() override;
void init_step_dir_pins();
diff --git a/Grbl_Esp32/src/Motors/TrinamicDriver.cpp b/Grbl_Esp32/src/Motors/TrinamicDriver.cpp
index 108d9556..916290be 100644
--- a/Grbl_Esp32/src/Motors/TrinamicDriver.cpp
+++ b/Grbl_Esp32/src/Motors/TrinamicDriver.cpp
@@ -65,7 +65,6 @@ namespace Motors {
}
_has_errors = false;
- init_step_dir_pins(); // from StandardStepper
_cs_pin.setAttr(Pin::Attr::Output | Pin::Attr::InitialOn);
@@ -115,7 +114,7 @@ namespace Motors {
NULL, // parameters
1, // priority
NULL,
- 0 // core
+ SUPPORT_TASK_CORE // must run the task on same core
);
}
} else {
@@ -216,6 +215,8 @@ namespace Motors {
tmcstepper->microsteps(_microsteps);
tmcstepper->rms_current(run_i_ma, hold_i_percent);
+
+ init_step_dir_pins();
}
bool TrinamicDriver::set_homing_mode(bool isHoming) {
@@ -265,7 +266,7 @@ namespace Motors {
tmcstepper->THIGH(calc_tstep(feedrate, 60.0));
tmcstepper->sfilt(1);
tmcstepper->diag1_stall(true); // stallguard i/o is on diag1
- tmcstepper->sgt(_stallguard);
+ tmcstepper->sgt(constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63));
break;
}
default:
@@ -294,7 +295,7 @@ namespace Motors {
tmcstepper->stallguard(),
tmcstepper->sg_result(),
feedrate,
- _stallguard);
+ constrain(axis_settings[_axis_index]->stallguard->get(), -64, 63));
TMC2130_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
status.sr = tmcstepper->DRV_STATUS();
@@ -362,10 +363,6 @@ namespace Motors {
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) { // don't ever return from this or the task dies
- if (motorSettingChanged) {
- MachineConfig::instance()->_axes->read_settings();
- motorSettingChanged = false;
- }
if (stallguard_debug_mask->get() != 0) {
if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) {
for (TrinamicDriver* p = List; p; p = p->link) {
@@ -380,7 +377,9 @@ namespace Motors {
vTaskDelayUntil(&xLastWakeTime, xreadSg);
static UBaseType_t uxHighWaterMark = 0;
+#ifdef DEBUG_TASK_STACK
reportTaskStackSize(uxHighWaterMark);
+#endif
}
}
diff --git a/Grbl_Esp32/src/Motors/TrinamicUartDriver.h b/Grbl_Esp32/src/Motors/TrinamicUartDriver.h
new file mode 100644
index 00000000..440231a8
--- /dev/null
+++ b/Grbl_Esp32/src/Motors/TrinamicUartDriver.h
@@ -0,0 +1,135 @@
+#pragma once
+
+/*
+ TrinamicUartDriver.h
+
+ Part of Grbl_ESP32
+ 2020 - The Ant Team
+ 2020 - Bart Dring
+
+ Grbl 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. If not, see .
+*/
+
+#include "Motor.h"
+#include "StandardStepper.h"
+#include "../Uart.h"
+
+#include // https://github.com/teemuatlut/TMCStepper
+
+const float TMC2208_RSENSE_DEFAULT = 0.11f;
+const float TMC2209_RSENSE_DEFAULT = 0.11f;
+
+const double TRINAMIC_UART_FCLK = 12700000.0; // Internal clock Approx (Hz) used to calculate TSTEP from homing rate
+
+// ==== defaults OK to define them in your machine definition ====
+
+#ifndef TRINAMIC_UART_RUN_MODE
+# define TRINAMIC_UART_RUN_MODE TrinamicUartMode ::StealthChop
+#endif
+
+#ifndef TRINAMIC_UART_HOMING_MODE
+# define TRINAMIC_UART_HOMING_MODE TRINAMIC_UART_RUN_MODE
+#endif
+
+#ifndef TRINAMIC_UART_TOFF_DISABLE
+# define TRINAMIC_UART_TOFF_DISABLE 0
+#endif
+
+#ifndef TRINAMIC_UART_TOFF_STEALTHCHOP
+# define TRINAMIC_UART_TOFF_STEALTHCHOP 5
+#endif
+
+#ifndef TRINAMIC_UART_TOFF_COOLSTEP
+# define TRINAMIC_UART_TOFF_COOLSTEP 3
+#endif
+
+#ifndef TMC_UART
+# define TMC_UART UART_NUM_2
+#endif
+
+#ifndef TMC_UART_RX
+# define TMC_UART_RX UNDEFINED_PIN
+#endif
+
+#ifndef TMC_UART_TX
+# define TMC_UART_TX UNDEFINED_PIN
+#endif
+
+extern Uart tmc_serial;
+
+namespace Motors {
+
+ enum class TrinamicUartMode : uint8_t {
+ None = 0, // not for machine defs!
+ StealthChop = 1,
+ CoolStep = 2,
+ StallGuard = 3,
+ };
+
+ class TrinamicUartDriver : public StandardStepper {
+ private:
+ static bool _uart_started;
+
+ public:
+ TrinamicUartDriver(uint8_t axis_index,
+ uint8_t step_pin,
+ uint8_t dir_pin,
+ uint8_t disable_pin,
+ uint16_t driver_part_number,
+ float r_senseS,
+ uint8_t address);
+
+ void config_message();
+ void hw_serial_init();
+ void init();
+ void set_mode();
+ void read_settings();
+ void debug_message();
+ bool set_homing_mode(bool is_homing) override;
+ void set_disable(bool disable) override;
+
+ uint8_t addr;
+
+ private:
+ uint32_t calc_tstep(float speed, float percent); //TODO: see if this is useful/used.
+
+ TMC2209Stepper* tmcstepper; // all other driver types are subclasses of this one
+ TrinamicUartMode _homing_mode;
+ uint16_t _driver_part_number; // example: use 2209 for TMC2209
+ float _r_sense;
+ bool _has_errors;
+ bool _disabled;
+
+ TrinamicUartMode _mode = TrinamicUartMode::None;
+ bool test();
+ void set_mode(bool isHoming);
+ void trinamic_test_response();
+ void trinamic_stepper_enable(bool enable);
+
+ bool report_open_load(TMC2208_n ::DRV_STATUS_t status);
+ bool report_short_to_ground(TMC2208_n ::DRV_STATUS_t status);
+ bool report_over_temp(TMC2208_n ::DRV_STATUS_t status);
+ bool report_short_to_ps(TMC2208_n ::DRV_STATUS_t status);
+
+ uint8_t get_next_index();
+
+ // Linked list of Trinamic driver instances, used by the
+ // StallGuard reporting task. TODO: verify if this is really used/useful.
+ static TrinamicUartDriver* List;
+ TrinamicUartDriver* link;
+ static void readSgTask(void*);
+
+ protected:
+ // void config_message() override;
+ };
+
+}
diff --git a/Grbl_Esp32/src/Motors/TrinamicUartDriverClass.cpp b/Grbl_Esp32/src/Motors/TrinamicUartDriverClass.cpp
new file mode 100644
index 00000000..6409f1e6
--- /dev/null
+++ b/Grbl_Esp32/src/Motors/TrinamicUartDriverClass.cpp
@@ -0,0 +1,401 @@
+/*
+ TrinamicUartDriverClass.cpp
+
+ This is used for Trinamic UART controlled stepper motor drivers.
+
+ Part of Grbl_ESP32
+ 2020 - The Ant Team
+ 2020 - Bart Dring
+
+ TMC2209 Datasheet
+ https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2209_Datasheet_V103.pdf
+
+ Grbl 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. If not, see .
+
+*/
+#include "TrinamicUartDriver.h"
+
+#include
+
+Uart tmc_serial(TMC_UART);
+
+namespace Motors {
+
+ bool TrinamicUartDriver::_uart_started = false;
+
+ TrinamicUartDriver* TrinamicUartDriver::List = NULL; // a static ist of all drivers for stallguard reporting
+
+ /* HW Serial Constructor. */
+ TrinamicUartDriver::TrinamicUartDriver(
+ uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin, uint16_t driver_part_number, float r_sense, uint8_t addr) :
+ StandardStepper(axis_index, step_pin, dir_pin, disable_pin) {
+ _driver_part_number = driver_part_number;
+ _has_errors = false;
+ _r_sense = r_sense;
+ this->addr = addr;
+
+ if (!_uart_started) {
+ tmc_serial.setPins(TMC_UART_TX, TMC_UART_RX);
+ tmc_serial.begin(115200, Uart::Data::Bits8, Uart::Stop::Bits1, Uart::Parity::None);
+ _uart_started = true;
+ }
+ hw_serial_init();
+
+ link = List;
+ List = this;
+ }
+
+ void TrinamicUartDriver::hw_serial_init() {
+ if (_driver_part_number == 2209)
+ tmcstepper = new TMC2209Stepper(&tmc_serial, _r_sense, addr);
+ else {
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unsupported Trinamic motor p/n:%d", _driver_part_number);
+ return;
+ }
+ }
+
+ void TrinamicUartDriver ::init() {
+ if (_has_errors) {
+ return;
+ }
+
+ init_step_dir_pins(); // from StandardStepper
+ config_message();
+
+ tmcstepper->begin();
+
+ _has_errors = !test(); // Try communicating with motor. Prints an error if there is a problem.
+
+ /* If communication with the driver is working, read the
+ main settings, apply new driver settings and then read
+ them back. */
+ if (!_has_errors) { //TODO: verify if this is the right way to set the Irun/IHold and microsteps.
+ read_settings();
+ set_mode(false);
+ }
+
+ // After initializing all of the TMC drivers, create a task to
+ // display StallGuard data. List == this for the final instance.
+ if (List == this) {
+ xTaskCreatePinnedToCore(readSgTask, // task
+ "readSgTask", // name for task
+ 4096, // size of task stack
+ NULL, // parameters
+ 1, // priority
+ NULL,
+ SUPPORT_TASK_CORE // must run the task on same core
+ // core
+ );
+ }
+ }
+
+ /*
+ This is the startup message showing the basic definition.
+ */
+ void TrinamicUartDriver::config_message() { //TODO: The RX/TX pin could be added to the msg.
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s motor Trinamic TMC%d Step:%s Dir:%s Disable:%s UART%d Rx:%s Tx:%s Addr:%d R:%0.3f %s",
+ reportAxisNameMsg(_axis_index, _dual_axis_index),
+ _driver_part_number,
+ pinName(_step_pin).c_str(),
+ pinName(_dir_pin).c_str(),
+ pinName(_disable_pin).c_str(),
+ TMC_UART,
+ pinName(TMC_UART_RX),
+ pinName(TMC_UART_TX),
+ this->addr,
+ _r_sense,
+ reportAxisLimitsMsg(_axis_index));
+ }
+
+ bool TrinamicUartDriver::test() {
+ if (_has_errors) {
+ return false;
+ }
+ switch (tmcstepper->test_connection()) {
+ case 1:
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s driver test failed. Check connection",
+ reportAxisNameMsg(_axis_index, _dual_axis_index));
+ return false;
+ case 2:
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s driver test failed. Check motor power",
+ reportAxisNameMsg(_axis_index, _dual_axis_index));
+ return false;
+ default:
+ // driver responded, so check for other errors from the DRV_STATUS register
+
+ TMC2208_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
+ status.sr = tmcstepper->DRV_STATUS();
+
+ bool err = false;
+
+ // look for errors
+ if (report_short_to_ground(status)) {
+ err = true;
+ }
+
+ if (report_over_temp(status)) {
+ err = true;
+ }
+
+ if (report_short_to_ps(status)) {
+ err = true;
+ }
+
+ if (err) {
+ return false;
+ }
+
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s driver test passed", reportAxisNameMsg(_axis_index, _dual_axis_index));
+ return true;
+ }
+ }
+
+ /*
+ Read setting and send them to the driver. Called at init() and whenever related settings change
+ both are stored as float Amps, but TMCStepper library expects...
+ uint16_t run (mA)
+ float hold (as a percentage of run)
+ */
+ void TrinamicUartDriver::read_settings() {
+ if (_has_errors) {
+ return;
+ }
+
+ uint16_t run_i_ma = (uint16_t)(axis_settings[_axis_index]->run_current->get() * 1000.0);
+ float hold_i_percent;
+
+ if (axis_settings[_axis_index]->run_current->get() == 0)
+ hold_i_percent = 0;
+ else {
+ hold_i_percent = axis_settings[_axis_index]->hold_current->get() / axis_settings[_axis_index]->run_current->get();
+ if (hold_i_percent > 1.0)
+ hold_i_percent = 1.0;
+ }
+ tmcstepper->microsteps(axis_settings[_axis_index]->microsteps->get());
+ tmcstepper->rms_current(run_i_ma, hold_i_percent);
+
+ // grbl_msg_sendf(CLIENT_SERIAL,
+ // MsgLevel::Info,
+ // "Setting current of driver %s, target: %u, read irun: %d, hold percent: %f, usteps: %d",
+ // reportAxisNameMsg(_axis_index, _dual_axis_index), run_i_ma, tmcstepper->rms_current(), hold_i_percent, axis_settings[_axis_index]->microsteps->get());
+ }
+
+ bool TrinamicUartDriver::set_homing_mode(bool isHoming) {
+ set_mode(isHoming);
+ return true;
+ }
+
+ /*
+ There are ton of settings. I'll start by grouping then into modes for now.
+ Many people will want quiet and stallgaurd homing. Stallguard only run in
+ Coolstep mode, so it will need to switch to Coolstep when homing
+ */
+ void TrinamicUartDriver::set_mode(bool isHoming) {
+ if (_has_errors) {
+ return;
+ }
+
+ TrinamicUartMode newMode = isHoming ? TRINAMIC_UART_HOMING_MODE : TRINAMIC_UART_RUN_MODE;
+
+ if (newMode == _mode) {
+ return;
+ }
+
+ _mode = newMode;
+
+ switch (_mode) {
+ case TrinamicUartMode ::StealthChop:
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "StealthChop");
+ tmcstepper->en_spreadCycle(false);
+ tmcstepper->pwm_autoscale(true);
+ break;
+ case TrinamicUartMode ::CoolStep:
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Coolstep");
+ // tmcstepper->en_pwm_mode(false); //TODO: check if this is present in TMC2208/09
+ tmcstepper->en_spreadCycle(true);
+ tmcstepper->pwm_autoscale(false);
+ break;
+ case TrinamicUartMode ::StallGuard: //TODO: check all configurations for stallguard
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Stallguard");
+ tmcstepper->en_spreadCycle(false);
+ tmcstepper->pwm_autoscale(false);
+ tmcstepper->TCOOLTHRS(calc_tstep(homing_feed_rate->get(), 150.0));
+ tmcstepper->SGTHRS(constrain(axis_settings[_axis_index]->stallguard->get(), 0, 255));
+ break;
+ default:
+ grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Unknown Trinamic mode:d", _mode);
+ }
+ }
+
+ /*
+ This is the stallguard tuning info. It is call debug, so it could be generic across all classes.
+ */
+ void TrinamicUartDriver::debug_message() {
+ if (_has_errors) {
+ return;
+ }
+ uint32_t tstep = tmcstepper->TSTEP();
+
+ if (tstep == 0xFFFFF || tstep < 1) { // if axis is not moving return
+ return;
+ }
+ float feedrate = st_get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
+
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
+ reportAxisNameMsg(_axis_index, _dual_axis_index),
+ tmcstepper->SG_RESULT(), // tmcstepper->sg_result(),
+ feedrate,
+ axis_settings[_axis_index]->stallguard->get());
+
+ TMC2208_n ::DRV_STATUS_t status { 0 }; // a useful struct to access the bits.
+ status.sr = tmcstepper->DRV_STATUS();
+
+ // these only report if there is a fault condition
+ report_open_load(status);
+ report_short_to_ground(status);
+ report_over_temp(status);
+ report_short_to_ps(status);
+ }
+
+ // calculate a tstep from a rate
+ // tstep = TRINAMIC_UART_FCLK / (time between 1/256 steps)
+ // This is used to set the stallguard window from the homing speed.
+ // The percent is the offset on the window
+ uint32_t TrinamicUartDriver::calc_tstep(float speed, float percent) {
+ float tstep =
+ speed / 60.0 * axis_settings[_axis_index]->steps_per_mm->get() * (float)(256 / axis_settings[_axis_index]->microsteps->get());
+ tstep = TRINAMIC_UART_FCLK / tstep * percent / 100.0;
+
+ return static_cast(tstep);
+ }
+
+ // this can use the enable feature over SPI. The dedicated pin must be in the enable mode,
+ // but that can be hardwired that way.
+ void TrinamicUartDriver::set_disable(bool disable) {
+ if (_has_errors) {
+ return;
+ }
+
+ if (_disabled == disable) {
+ return;
+ }
+
+ _disabled = disable;
+
+ digitalWrite(_disable_pin, _disabled);
+
+#ifdef USE_TRINAMIC_ENABLE
+ if (_disabled) {
+ tmcstepper->toff(TRINAMIC_UART_TOFF_DISABLE);
+ } else {
+ if (_mode == TrinamicUartMode::StealthChop) {
+ tmcstepper->toff(TRINAMIC_UART_TOFF_STEALTHCHOP);
+ } else {
+ tmcstepper->toff(TRINAMIC_UART_TOFF_COOLSTEP);
+ }
+ }
+#endif
+ // the pin based enable could be added here.
+ // This would be for individual motors, not the single pin for all motors.
+ }
+
+ // =========== Reporting functions ========================
+
+ bool TrinamicUartDriver::report_open_load(TMC2208_n ::DRV_STATUS_t status) {
+ if (status.ola || status.olb) {
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s Driver open load A:%s B:%s",
+ reportAxisNameMsg(_axis_index, _dual_axis_index),
+ status.ola ? "Y" : "N",
+ status.olb ? "Y" : "N");
+ return true;
+ }
+ return false; // no error
+ }
+
+ bool TrinamicUartDriver::report_short_to_ground(TMC2208_n ::DRV_STATUS_t status) {
+ if (status.s2ga || status.s2gb) {
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s Driver shorted coil A:%s B:%s",
+ reportAxisNameMsg(_axis_index, _dual_axis_index),
+ status.s2ga ? "Y" : "N",
+ status.s2gb ? "Y" : "N");
+ return true;
+ }
+ return false; // no error
+ }
+
+ bool TrinamicUartDriver::report_over_temp(TMC2208_n ::DRV_STATUS_t status) {
+ if (status.ot || status.otpw) {
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s Driver temp Warning:%s Fault:%s",
+ reportAxisNameMsg(_axis_index, _dual_axis_index),
+ status.otpw ? "Y" : "N",
+ status.ot ? "Y" : "N");
+ return true;
+ }
+ return false; // no error
+ }
+
+ bool TrinamicUartDriver::report_short_to_ps(TMC2208_n ::DRV_STATUS_t status) {
+ // check for short to power supply
+ if ((status.sr & bit(12)) || (status.sr & bit(13))) {
+ grbl_msg_sendf(CLIENT_SERIAL,
+ MsgLevel::Info,
+ "%s Driver short vsa:%s vsb:%s",
+ reportAxisNameMsg(_axis_index, _dual_axis_index),
+ (status.sr & bit(12)) ? "Y" : "N",
+ (status.sr & bit(13)) ? "Y" : "N");
+ return true;
+ }
+ return false; // no error
+ }
+
+ // Prints StallGuard data that is useful for tuning.
+ void TrinamicUartDriver::readSgTask(void* pvParameters) {
+ TickType_t xLastWakeTime;
+ const TickType_t xreadSg = 200; // in ticks (typically ms)
+ auto n_axis = number_axis->get();
+
+ xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
+ while (true) { // don't ever return from this or the task dies
+ if (stallguard_debug_mask->get() != 0) {
+ if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) {
+ for (TrinamicUartDriver* p = List; p; p = p->link) {
+ if (bitnum_istrue(stallguard_debug_mask->get(), p->_axis_index)) {
+ //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SG:%d", stallguard_debug_mask->get());
+ p->debug_message();
+ }
+ }
+ } // sys.state
+ } // if mask
+
+ vTaskDelayUntil(&xLastWakeTime, xreadSg);
+
+ static UBaseType_t uxHighWaterMark = 0;
+#ifdef DEBUG_TASK_STACK
+ reportTaskStackSize(uxHighWaterMark);
+#endif
+ }
+ }
+}
diff --git a/Grbl_Esp32/src/NutsBolts.cpp b/Grbl_Esp32/src/NutsBolts.cpp
index 358a201a..a1b34fc6 100644
--- a/Grbl_Esp32/src/NutsBolts.cpp
+++ b/Grbl_Esp32/src/NutsBolts.cpp
@@ -114,23 +114,28 @@ void delay_ms(uint16_t ms) {
}
// Non-blocking delay function used for general operation and suspend features.
-void delay_sec(float seconds, uint8_t mode) {
- uint16_t i = ceil(1000 / DWELL_TIME_STEP * seconds);
+bool delay_msec(int32_t milliseconds, DwellMode mode) {
+ // Note: i must be signed, because of the 'i-- > 0' check below.
+ int32_t i = milliseconds / DWELL_TIME_STEP;
+ int32_t remainder = i < 0 ? 0 : (milliseconds - DWELL_TIME_STEP * i);
+
while (i-- > 0) {
if (sys.abort) {
- return;
+ return false;
}
- if (mode == DELAY_MODE_DWELL) {
+ if (mode == DwellMode::Dwell) {
protocol_execute_realtime();
- } else { // DELAY_MODE_SYS_SUSPEND
+ } else { // DwellMode::SysSuspend
// Execute rt_system() only to avoid nesting suspend loops.
protocol_exec_rt_system();
if (sys.suspend.bit.restartRetract) {
- return; // Bail, if safety door reopens.
+ return false; // Bail, if safety door reopens.
}
}
delay(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
}
+ delay(remainder);
+ return true;
}
// Simple hypotenuse computation function.
diff --git a/Grbl_Esp32/src/NutsBolts.h b/Grbl_Esp32/src/NutsBolts.h
index 7a115f2a..3c65659e 100644
--- a/Grbl_Esp32/src/NutsBolts.h
+++ b/Grbl_Esp32/src/NutsBolts.h
@@ -27,6 +27,11 @@
#define UNDEFINED_PIN ""
+enum class DwellMode : uint8_t {
+ Dwell = 0, // (Default: Must be zero)
+ SysSuspend = 1, //G92.1 (Do not alter value)
+};
+
const double SOME_LARGE_VALUE = 1.0E+38;
// Axis array index values. Must start with 0 and be continuous.
@@ -59,9 +64,6 @@ static inline int toMotor2(int axis) {
const double MM_PER_INCH = (25.40);
const double INCH_PER_MM = (0.0393701);
-const int DELAY_MODE_DWELL = 0;
-const int DELAY_MODE_SYS_SUSPEND = 1;
-
// Useful macros
#define clear_vector(a) memset(a, 0, sizeof(a))
#define clear_vector_float(a) memset(a, 0.0, sizeof(float) * MAX_N_AXIS)
@@ -89,7 +91,7 @@ const int DELAY_MODE_SYS_SUSPEND = 1;
uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr);
// Non-blocking delay function used for general operation and suspend features.
-void delay_sec(float seconds, uint8_t mode);
+bool delay_msec(int32_t milliseconds, DwellMode mode);
// Delays variable-defined milliseconds. Compiler compatibility fix for _delay_ms().
void delay_ms(uint16_t ms);
diff --git a/Grbl_Esp32/src/Planner.h b/Grbl_Esp32/src/Planner.h
index 1f5f3eb4..812229c9 100644
--- a/Grbl_Esp32/src/Planner.h
+++ b/Grbl_Esp32/src/Planner.h
@@ -91,6 +91,7 @@ typedef struct {
#ifdef USE_LINE_NUMBERS
int32_t line_number; // Desired line number to report when executing.
#endif
+ bool is_jog; // true if this was generated due to a jog command
} plan_line_data_t;
// Initialize and reset the motion plan subsystem
diff --git a/Grbl_Esp32/src/Probe.cpp b/Grbl_Esp32/src/Probe.cpp
index d371ade6..831e9a37 100644
--- a/Grbl_Esp32/src/Probe.cpp
+++ b/Grbl_Esp32/src/Probe.cpp
@@ -54,7 +54,7 @@ void Probe::set_direction(bool is_away) {
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
bool Probe::get_state() {
- return _probePin.read() ^ probe_invert->get();
+ return _probePin.undefined() ? false : _probePin.read() ^ probe_invert->get();
}
// Monitors probe pin state and records the system position when detected. Called by the
@@ -70,7 +70,6 @@ void Probe::state_monitor() {
void Probe::validate() const {}
-void Probe::handle(Configuration::HandlerBase& handler)
-{
+void Probe::handle(Configuration::HandlerBase& handler) {
handler.handle("pin", _probePin);
}
diff --git a/Grbl_Esp32/src/ProcessSettings.cpp b/Grbl_Esp32/src/ProcessSettings.cpp
index d77945b9..1e65d29c 100644
--- a/Grbl_Esp32/src/ProcessSettings.cpp
+++ b/Grbl_Esp32/src/ProcessSettings.cpp
@@ -1,5 +1,6 @@
#include "Grbl.h"
#include