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

Big homing fixup

This commit is contained in:
Mitch Bradley
2021-05-24 11:24:47 -10:00
parent 7b3f9e43da
commit 5ca34f9911
20 changed files with 258 additions and 497 deletions

View File

@@ -73,7 +73,11 @@ static void cartesian_to_motors(float* position) {
// 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) {
bool user_defined_homing(AxisMask cycle_mask) {
if (!config->_homing) {
log_error("Homing is not configured");
return true;
}
uint8_t n_cycle; // each home is a multi cycle operation approach, pulloff, approach.....
float target[MAX_N_AXIS] = { 0.0 }; // The target for each move in the cycle
float max_travel;
@@ -123,7 +127,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
if (bit(axis) == mask) {
// setup for the homing of this axis
bool approach = true;
float homing_rate = homing_seek_rate->get();
float homing_rate = config->_homing->_seekRate;
max_travel = HOMING_AXIS_SEARCH_SCALAR * config->_axes->_axis[axis]->_maxTravel;
sys.homing_axis_lock = 0xFF; // we don't need to lock any motors in CoreXY
n_cycle = (2 * NHomingLocateCycle + 1); // approach + ((pulloff + approach) * Cycles)
@@ -203,17 +207,17 @@ bool user_defined_homing(uint8_t cycle_mask) {
}
}
#endif
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(homing_debounce->get()); // Delay to allow transient dynamics to dissipate.
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(config->_homing->_debounce); // Delay to allow transient dynamics to dissipate.
approach = !approach;
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
if (approach) {
max_travel = homing_pulloff->get() * HOMING_AXIS_LOCATE_SCALAR;
homing_rate = homing_feed_rate->get();
max_travel = config->_homing->_pulloff * HOMING_AXIS_LOCATE_SCALAR;
homing_rate = config->_homing->_feedRate;
} else {
max_travel = homing_pulloff->get();
homing_rate = homing_seek_rate->get();
max_travel = config->_homing->_pulloff;
homing_rate = config->_homing->_seekRate;
}
} while (n_cycle-- > 0);
}
@@ -225,9 +229,9 @@ bool user_defined_homing(uint8_t cycle_mask) {
// set the cartesian axis position
for (axis = X_AXIS; axis <= Y_AXIS; axis++) {
if (bitnum_istrue(homing_dir_mask->get(), axis)) {
target[axis] = limitsMinPosition(axis) + homing_pulloff->get();
target[axis] = limitsMinPosition(axis) + config->_homing->_pulloff;
} else {
target[axis] = limitsMaxPosition(axis) - homing_pulloff->get();
target[axis] = limitsMaxPosition(axis) - config->_homing->_pulloff;
}
}
@@ -304,7 +308,7 @@ void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
}
}
bool kinematics_pre_homing(uint8_t cycle_mask) {
bool kinematics_pre_homing(AxisMask cycle_mask) {
return false;
}

View File

@@ -90,7 +90,7 @@ void solenoidSyncTask(void* pvParameters) {
// continue with regular homing after setup
// return true if this completes homing
bool user_defined_homing(uint8_t cycle_mask) {
bool user_defined_homing(AxisMask cycle_mask) {
// create and start a task to do the special homing
homing_phase = HOMING_PHASE_FULL_APPROACH;
atari_homing = true;

View File

@@ -58,13 +58,13 @@ bool limitsCheckTravel() {
}
/*
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
user_defined_homing is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing returns false, the rest of normal Grbl_ESP32
homing is skipped if it returns false, other normal homing continues. For
example, if you need to manually prep the machine for homing, you could implement
user_defined_homing(uint8_t cycle_mask) to wait for some button to be pressed, then return true.
user_defined_homing to wait for some button to be pressed, then return true.
*/
bool user_defined_homing(uint8_t cycle_mask) {
bool user_defined_homing(AxisMask cycle_mask) {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}
@@ -91,12 +91,12 @@ bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* positi
}
/*
kinematics_pre_homing() is called before normal homing
kinematics_pre_homing is called before normal homing
You can use it to do special homing or just to set stuff up
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(AxisMask cycle_mask) {
return false; // finish normal homing cycle
}

View File

@@ -4,8 +4,6 @@
copyright (c) 2020 - Bart Dring. This file was intended for use on the ESP32
...add your date and name here.
CPU. Do not use this with Grbl for atMega328P
Grbl_ESP32 is free software: you can redistribute it and/or modify
@@ -21,47 +19,19 @@
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
=======================================================================
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.
To use this file, copy it to a name of your own choosing, and also copy
Machines/template.h to a similar name.
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
===============================================================================
*/
#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.
*/
# define STEPPERS_DISABLE_PIN_X 138
# define STEPPERS_DISABLE_PIN_Y 134
# define STEPPERS_DISABLE_PIN_Z 131
# define STEPPERS_DISABLE_PIN_A 139
#define STEPPERS_DISABLE_PIN_X 138
#define STEPPERS_DISABLE_PIN_Y 134
#define STEPPERS_DISABLE_PIN_Z 131
#define STEPPERS_DISABLE_PIN_A 139
# define FAN1_PIN 13
# define FAN2_PIN 142
# define FAN3_PIN 143
#define FAN1_PIN 13
#define FAN2_PIN 142
#define FAN3_PIN 143
# define BED_PIN 4
# define NOZZLE_PIN 2
#define BED_PIN 4
#define NOZZLE_PIN 2
void machine_init() {
// Enable steppers
@@ -78,106 +48,3 @@ void machine_init() {
digitalWrite(BED_PIN, LOW); // disable
digitalWrite(NOZZLE_PIN, LOW); // disable
}
#endif
#ifdef USE_CUSTOM_HOMING
/*
(user_defined_homing) is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing() returns false, the rest of normal Grbl_ESP32
homing is skipped if it returns false, other normal homing continues. For
example, if you need to manually prep the machine for homing, you could implement
user_defined_homing() to wait for some button to be pressed, then return true.
*/
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.
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
Grbl_ESP32 for examples. You are basically converting cartesian X,Y,Z... targets to
target = an N_AXIS array of target positions (where the move is supposed to go)
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) {
// this simply moves to the target. Replace with your kinematics.
mc_line(target, pl_data);
}
/*
kinematics_pre_homing() is called before normal homing
You can use it to do special homing or just to set stuff up
cycle_mask is a bit mask of the axes being homed this time.
*/
bool kinematics_pre_homing(uint8_t cycle_mask))
{
return false; // finish normal homing cycle
}
/*
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
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) {
// 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
// #ifdef USE_WHATEVER and add function prototypes (also guarded) to grbl.h

View File

@@ -124,14 +124,6 @@ void machine_init() {
// 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
// }
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];

View File

@@ -170,12 +170,6 @@ const int DEFAULT_RADIO_MODE = ESP_RADIO_OFF;
// greater.
static const uint8_t NHomingLocateCycle = 1; // Integer (1-128)
// Enables single axis homing commands. $HX, $HY, and $HZ for X, Y, and Z-axis homing. The full homing
// cycle is still invoked by the $H command. This is disabled by default. It's here only to address
// users that need to switch between a two-axis and three-axis machine. This is actually very rare.
// If you have a two-axis machine, DON'T USE THIS. Instead, just alter the homing cycle for two-axes.
#define HOMING_SINGLE_AXIS_COMMANDS // Default disabled. Uncomment to enable.
// Number of blocks Grbl executes upon startup. These blocks are stored in non-volatile storage.
// and addresses are defined in settings.h. With the current settings, up to 2 startup blocks may
// be stored and executed in order. These startup blocks would typically be used to set the GCode

View File

@@ -42,102 +42,13 @@
# define DEFAULT_STATUS_REPORT_MASK 1 // $10
#endif
#ifndef DEFAULT_HOMING_ENABLE
# define DEFAULT_HOMING_ENABLE 0 // $22 false
#endif
#ifndef DEFAULT_HOMING_DIR_MASK
# define DEFAULT_HOMING_DIR_MASK 3 // $23 move positive dir Z, negative X,Y
#endif
#ifndef DEFAULT_HOMING_FEED_RATE
# define DEFAULT_HOMING_FEED_RATE 200.0 // $24 mm/min
#endif
#ifndef DEFAULT_HOMING_SEEK_RATE
# define DEFAULT_HOMING_SEEK_RATE 2000.0 // $25 mm/min
#endif
#ifndef DEFAULT_HOMING_DEBOUNCE_DELAY
# define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // $26 msec (0-65k)
#endif
#ifndef DEFAULT_HOMING_PULLOFF
# define DEFAULT_HOMING_PULLOFF 1.0 // $27 mm
#endif
#ifndef DEFAULT_HOMING_SQUARED_AXES
# define DEFAULT_HOMING_SQUARED_AXES 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_0
# define DEFAULT_HOMING_CYCLE_0 bit(Z_AXIS)
#endif
#ifndef DEFAULT_HOMING_CYCLE_1
# define DEFAULT_HOMING_CYCLE_1 (bit(X_AXIS) | bit(Y_AXIS))
#endif
#ifndef DEFAULT_HOMING_CYCLE_2
# define DEFAULT_HOMING_CYCLE_2 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_3
# define DEFAULT_HOMING_CYCLE_3 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_4
# define DEFAULT_HOMING_CYCLE_4 0
#endif
#ifndef DEFAULT_HOMING_CYCLE_5
# define DEFAULT_HOMING_CYCLE_5 0
#endif
// ======== SPINDLE STUFF ====================
#ifndef SPINDLE_TYPE
# define SPINDLE_TYPE SpindleType::NONE
#endif
// ================ user settings =====================
#ifndef DEFAULT_USER_INT_80
# define DEFAULT_USER_INT_80 0 // $80 User integer setting
#endif
#ifndef DEFAULT_USER_INT_81
# define DEFAULT_USER_INT_81 0 // $81 User integer setting
#endif
#ifndef DEFAULT_USER_INT_82
# define DEFAULT_USER_INT_82 0 // $82 User integer setting
#endif
#ifndef DEFAULT_USER_INT_83
# define DEFAULT_USER_INT_83 0 // $83 User integer setting
#endif
#ifndef DEFAULT_USER_INT_84
# define DEFAULT_USER_INT_84 0 // $84 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_90
# define DEFAULT_USER_FLOAT_90 0.0 // $90 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_91
# define DEFAULT_USER_FLOAT_91 0.0 // $92 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_92
# define DEFAULT_USER_FLOAT_92 0.0 // $92 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_93
# define DEFAULT_USER_FLOAT_93 0.0 // $93 User integer setting
#endif
#ifndef DEFAULT_USER_FLOAT_94
# define DEFAULT_USER_FLOAT_94 0.0 // $94 User integer setting
#ifndef SERVO_TIMER_INTERVAL
# define SERVO_TIMER_INTERVAL 75.0 // Hz This is the update inveral in milliseconds
#endif
// ================== pin defaults ========================
@@ -150,10 +61,6 @@
# define SDCARD_DET_PIN UNDEFINED_PIN
#endif
#ifndef SERVO_TIMER_INTERVAL
# define SERVO_TIMER_INTERVAL 75.0 // Hz This is the update inveral in milliseconds
#endif
// ================ User Digital I/O ==============================
#ifndef USER_DIGITAL_PIN_0

View File

@@ -85,7 +85,9 @@ void grbl_init() {
// not after disabling the alarm locks. Prevents motion startup blocks from crashing into
// things uncontrollably. Very bad.
#ifdef HOMING_INIT_LOCK
if (homing_enable->get()) {
// TODO: maybe HOMING_INIT_LOCK should be configurable
// If there is an axis with homing configured, enter Alarm state on startup
if (homingAxes()) {
sys.state = State::Alarm;
}
#endif

View File

@@ -94,11 +94,11 @@ void run_once();
// Weak definitions that can be overridden
void machine_init();
void display_init();
bool user_defined_homing(uint8_t cycle_mask);
bool user_defined_homing(AxisMask cycle_mask);
// 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);
bool kinematics_pre_homing(AxisMask cycle_mask);
void kinematics_post_homing();
bool limitsCheckTravel(float* target); // weak in Limits.cpp; true if out of range

View File

@@ -28,8 +28,6 @@
#include "Grbl.h"
#include "MachineConfig.h"
uint8_t n_homing_locate_cycle = NHomingLocateCycle;
xQueueHandle limit_sw_queue; // used by limit switch debouncing
// Homing axis search distance multiplier. Computed by this value times the cycle travel.
@@ -70,6 +68,19 @@ void IRAM_ATTR isr_limit_switches(void* /*unused */) {
}
}
AxisMask homingAxes() {
AxisMask mask = 0;
auto axes = config->_axes;
auto n_axis = axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
auto homing = axes->_axis[axis]->_homing;
if (homing) {
bitnum_true(mask, axis);
}
}
return mask;
}
// Homes the specified cycle axes, sets the machine position, and performs a pull-off motion after
// completing. Homing is a special motion case, which involves rapid uncontrolled stops to locate
// the trigger point of the limit switches. The rapid stops are handled by a system level axis lock
@@ -77,7 +88,10 @@ void IRAM_ATTR isr_limit_switches(void* /*unused */) {
// circumvent the processes for executing motions in normal operation.
// NOTE: Only the abort realtime command can interrupt this process.
// TODO: Move limit pin-specific calls to a general function for portability.
void limits_go_home(uint8_t cycle_mask) {
void limits_go_home(uint8_t cycle_mask, uint n_locate_cycles) {
if ((cycle_mask & homingAxes()) != cycle_mask) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Debug, "Homing is not configured for some requested axes");
}
if (sys.abort) {
return; // Block if system reset has been issued.
}
@@ -88,7 +102,8 @@ void limits_go_home(uint8_t cycle_mask) {
// Motors with non standard homing can home during motors_set_homing_mode(...)
cycle_mask = config->_axes->set_homing_mode(cycle_mask, true); // tell motors homing is about to start
// see if any motors are left
// See if any motors are left. This could be 0 if none of the motors specified
// by the original value of cycle_mask is capable of standard homing.
if (cycle_mask == 0) {
return;
}
@@ -103,62 +118,88 @@ void limits_go_home(uint8_t cycle_mask) {
pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
#endif
// Initialize variables used for homing computations.
uint8_t n_cycle = (2 * n_homing_locate_cycle + 1);
uint8_t step_pin[MAX_N_AXIS];
float max_travel = 0.0;
uint8_t n_cycle = (2 * n_locate_cycles + 1);
auto n_axis = config->_axes->_numberAxis;
for (uint8_t idx = 0; idx < n_axis; idx++) {
// 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)*config->_axes->_axis[idx]->_maxTravel);
}
}
// Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
bool approach = true;
float homing_rate = homing_seek_rate->get(); // TODO FIXME: in YAML this is per-axis. We should move this into the loop.
bool approach = true;
uint8_t n_active_axis;
AxisMask limit_state, axislock;
float homing_rate = 0.0;
do {
float* target = system_get_mpos();
// Initialize and declare variables needed for homing routine.
axislock = 0;
n_active_axis = 0;
for (uint8_t idx = 0; idx < n_axis; idx++) {
auto axisConfig = config->_axes->_axis[idx];
// Set target location for active axes and setup computation for homing rate.
if (bit_istrue(cycle_mask, bit(idx))) {
n_active_axis++;
sys_position[idx] = 0;
// For multi-axis homing, we use the per-axis rates and travel limits to compute
// a target vector and a feedrate as follows:
// The goal is for each axis to travel at its specified rate, and for the
// maximum travel to be enough for each participating axis to reach its limit.
// For the rate goal, the axis components of the target vector must be proportional
// to the per-axis rates, and the overall feed rate must be the magnitude of the
// vector of per-axis rates.
// For the travel goal, the axis components of the target vector must be scaled
// according to the one that would take the longest.
// The time to complete a maxTravel move for a given feedRate is maxTravel/feedRate.
// We compute that time for all axes in the homing cycle, then find the longest one.
// Then we scale the travel distances for the other axes so they would complete
// at the same time.
axislock = 0;
float maxSeekTime = 0.0;
float limitingRate = 0.0;
int debounce = 0;
// Set target direction based on cycle mask and homing cycle approach state.
// NOTE: This happens to compile smaller than any other implementation tried.
auto mask = homing_dir_mask->get();
if (bit_istrue(mask, bit(idx))) {
if (approach) {
target[idx] = -max_travel;
} else {
target[idx] = max_travel;
}
} else {
if (approach) {
target[idx] = max_travel;
} else {
target[idx] = -max_travel;
for (int axis = 0; axis < n_axis; axis++) {
if (bitnum_isfalse(cycle_mask, axis)) {
continue;
}
auto axisConfig = config->_axes->_axis[axis];
auto homing = axisConfig->_homing;
if (homing != nullptr) {
auto axis_debounce = homing->_debounce;
if (axis_debounce > debounce) {
debounce = axis_debounce;
}
auto axis_homing_rate = approach ? homing->_seekRate : homing->_feedRate;
// Accumulate the squares of the homing rates for later use
// in computing the aggregate feed rate.
homing_rate += (axis_homing_rate * axis_homing_rate);
// Set target location for active axes and setup computation for homing rate.
if (bitnum_istrue(cycle_mask, axis)) {
sys_position[axis] = 0;
auto travel = approach ? axisConfig->_maxTravel : homing->_pulloff;
// First we compute the maximum time to completion vector; later we will
// convert it back to positions after we determine the limiting axis.
// Set target direction based on cycle mask and homing cycle approach state.
auto seekTime = travel / axis_homing_rate;
target[axis] = (homing->_positiveDirection ^ approach) ? -seekTime : seekTime;
if (seekTime > maxSeekTime) {
maxSeekTime = seekTime;
limitingRate = axis_homing_rate;
}
}
// Apply axislock to the step port pins active in this cycle.
axislock |= step_pin[idx];
// Record the axis as active
bitnum_true(axislock, axis);
}
}
homing_rate *= sqrt(n_active_axis); // [sqrt(number of active axis)] Adjust so individual axes all move at homing rate.
// Scale the target array, currently in units of time, back to positions
// The SCALAR adds a small fudge factor to ensure that the limit is reached
limitingRate *= approach ? HOMING_AXIS_SEARCH_SCALAR : HOMING_AXIS_LOCATE_SCALAR;
for (int axis = 0; axis < n_axis; axis++) {
if (bitnum_istrue(axislock, axis)) {
target[axis] *= limitingRate;
}
}
homing_rate = sqrt(homing_rate); // Magnitude of homing rate vector
sys.homing_axis_lock = axislock;
// Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
pl_data->feed_rate = homing_rate; // Set current homing rate.
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
pl_data->feed_rate = // Set current homing rate.
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
sys.step_control = {};
sys.step_control.executeSysMotion = true; // Set to execute homing motion and clear existing flags.
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
@@ -167,10 +208,10 @@ void limits_go_home(uint8_t cycle_mask) {
if (approach) {
// Check limit state. Lock out cycle axes when they change.
limit_state = limits_get_state();
for (uint8_t idx = 0; idx < n_axis; idx++) {
if (axislock & step_pin[idx]) {
if (limit_state & bit(idx)) {
axislock &= ~(step_pin[idx]);
for (int axis = 0; axis < n_axis; axis++) {
if (bitnum_istrue(axislock, axis)) {
if (bitnum_istrue(limit_state, axis)) {
bitnum_false(axislock, axis);
}
}
}
@@ -218,18 +259,10 @@ void limits_go_home(uint8_t cycle_mask) {
}
}
#endif
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(homing_debounce->get()); // Delay to allow transient dynamics to dissipate.
st_reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(debounce); // Delay to allow transient dynamics to dissipate.
// Reverse direction and reset homing rate for locate cycle(s).
approach = !approach;
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
if (approach) {
max_travel = homing_pulloff->get() * HOMING_AXIS_LOCATE_SCALAR;
homing_rate = homing_feed_rate->get();
} else {
max_travel = homing_pulloff->get();
homing_rate = homing_seek_rate->get();
}
} while (n_cycle-- > 0);
// The active cycle axes should now be homed and machine limits have been located. By
@@ -240,23 +273,17 @@ void limits_go_home(uint8_t cycle_mask) {
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
int32_t set_axis_position;
// Set machine positions for homed limit switches. Don't update non-homed axes.
auto mask = homing_dir_mask->get();
auto pulloff = homing_pulloff->get();
for (uint8_t idx = 0; idx < n_axis; idx++) {
Axis* axisConf = config->_axes->_axis[idx];
for (int axis = 0; axis < n_axis; axis++) {
Axis* axisConf = config->_axes->_axis[axis];
auto homing = axisConf->_homing;
auto steps = axisConf->_stepsPerMm;
if (cycle_mask & bit(idx)) {
float travel = axisConf->_maxTravel;
float mpos = 0;
if (axisConf->_homing != nullptr) {
mpos = axisConf->_homing->_mpos;
}
if (bit_istrue(homing_dir_mask->get(), bit(idx))) {
sys_position[idx] = (mpos + pulloff) * steps;
if (homing != nullptr && bitnum_istrue(cycle_mask, axis)) {
auto mpos = homing->_mpos;
auto pulloff = homing->_pulloff;
auto steps = axisConf->_stepsPerMm;
if (homing->_positiveDirection) {
sys_position[axis] = (mpos + pulloff) * steps;
} else {
sys_position[idx] = (mpos - pulloff) * steps;
sys_position[axis] = (mpos - pulloff) * steps;
}
}
}
@@ -284,7 +311,7 @@ void limits_init() {
#endif
pin.setAttr(mode);
limit_mask |= bit(axis);
bitnum_true(limit_mask, axis);
if (gangConfig->_endstops->_hardLimits) {
pin.attachInterrupt(isr_limit_switches, CHANGE, nullptr);
} else {
@@ -336,7 +363,7 @@ AxisMask limits_get_state() {
auto gangConfig = config->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
Pin& pin = gangConfig->_endstops->_dual;
pinMask |= (pin.read() << axis);
bitnum_true(pinMask, (pin.read() << axis));
}
}
}
@@ -415,13 +442,12 @@ float limitsMinPosition(uint8_t axis) {
// Return true if exceeding limits
// Set $<axis>/MaxTravel=0 to selectively remove an axis from soft limit checks
bool __attribute__((weak)) limitsCheckTravel(float* target) {
uint8_t idx;
auto n_axis = config->_axes->_numberAxis;
for (idx = 0; idx < n_axis; idx++) {
auto axes = config->_axes;
auto n_axis = axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
float max_mpos, min_mpos;
auto axisSetting = config->_axes->_axis[idx];
if ((target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) && axisSetting->_maxTravel > 0) {
auto axisSetting = axes->_axis[axis];
if ((target[axis] < limitsMinPosition(axis) || target[axis] > limitsMaxPosition(axis)) && axisSetting->_maxTravel > 0) {
return true;
}
}
@@ -438,6 +464,6 @@ bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
}
}
bool __attribute__((weak)) user_defined_homing(uint8_t cycle_mask) {
bool __attribute__((weak)) user_defined_homing(AxisMask cycle_mask) {
return false;
}

View File

@@ -27,19 +27,17 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
extern uint8_t n_homing_locate_cycle;
// Initialize the limits module
void limits_init();
// Disables hard limits.
void limits_disable();
// Returns limit state as a bit-wise uint8 variable.
// Returns limit state
AxisMask limits_get_state();
// Perform one portion of the homing cycle based on the input settings.
void limits_go_home(uint8_t cycle_mask);
// Perform one homing operation
void limits_go_home(AxisMask cycle_mask, uint n_locate_cycles);
// Check for soft limit violations
void limits_soft_check(float* target);
@@ -57,3 +55,5 @@ bool limitsCheckTravel(float* target);
// check if a switch has been defined
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index);
AxisMask homingAxes();

View File

@@ -202,32 +202,15 @@ void Axes::step(uint8_t step_mask, uint8_t dir_mask) {
}
}
// TODO FIXME: SdB This is not really correct... ganged_mode shouldn't be 'A' or 'B', but
// an index or a wildcard because for the new settings we have not bounded the number of
// gangs.
// Turn on step pulses for motors that are supposed to step now
for (int axis = X_AXIS; axis < _numberAxis; axis++) {
if (bitnum_istrue(step_mask, axis)) {
auto a = _axis[axis]->_gangs[0]->_motor;
if ((ganged_mode == SquaringMode::Dual) || (ganged_mode == SquaringMode::A)) {
a->step();
}
if ((ganged_mode == SquaringMode::Dual) || (ganged_mode == SquaringMode::B)) {
a->step();
}
}
}
for (uint8_t axis = X_AXIS; axis < n_axis; axis++) {
if (bitnum_istrue(step_mask, axis)) {
auto a = _axis[axis];
if ((ganged_mode == SquaringMode::Dual) || (ganged_mode == SquaringMode::A)) {
if (bitnum_istrue(ganged_mode, 0)) {
a->_gangs[0]->_motor->step();
}
if ((ganged_mode == SquaringMode::Dual) || (ganged_mode == SquaringMode::B)) {
if (bitnum_istrue(ganged_mode, 1)) {
a->_gangs[1]->_motor->step();
}
}

View File

@@ -46,12 +46,14 @@ class Homing : public Configuration::Configurable {
public:
Homing() = default;
int _cycle = -1;
bool _positiveDirection = true;
int _mpos = 0;
int _feedRate = 500;
int _seekRate = 100;
int _debounce = 10;
int _cycle = -1;
bool _square = false;
bool _positiveDirection = true;
float _mpos = 0;
float _feedRate = 500;
float _seekRate = 100;
float _pulloff = 1.0; // mm
int _debounce = 10;
// Configuration system helpers:
void validate() const override { Assert(_cycle >= 1, "Cycle has to be defined as >= 1 for homing sequence."); }
@@ -63,6 +65,8 @@ public:
handler.handle("feed_rate", _feedRate);
handler.handle("seek_rate", _seekRate);
handler.handle("debounce", _debounce);
handler.handle("pulloff", _pulloff);
handler.handle("square", _square);
}
};
@@ -83,7 +87,6 @@ public:
int _acceleration = 25;
int _maxTravel = 200;
bool _softLimits = false;
bool _autoSquaring = false;
// Configuration system helpers:
void validate() const override;

View File

@@ -32,7 +32,7 @@
# define M_PI 3.14159265358979323846
#endif
SquaringMode ganged_mode = SquaringMode::Dual;
GangMask ganged_mode = gangDual; // Run both motors at once
// 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
@@ -89,7 +89,6 @@ bool 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.
if (sys_pl_data_inflight == pl_data) {
plan_buffer_line(target, pl_data);
submitted_result = true;
@@ -102,7 +101,7 @@ bool __attribute__((weak)) cartesian_to_motors(float* target, plan_line_data_t*
return mc_line(target, pl_data);
}
bool __attribute__((weak)) kinematics_pre_homing(uint8_t cycle_mask) {
bool __attribute__((weak)) kinematics_pre_homing(AxisMask cycle_mask) {
return false; // finish normal homing cycle
}
@@ -254,7 +253,7 @@ bool mc_dwell(int32_t milliseconds) {
// return true if the mask has exactly one bit set,
// so it refers to exactly one axis
static bool mask_is_single_axis(uint8_t axis_mask) {
static bool mask_is_single_axis(AxisMask axis_mask) {
// This code depends on the fact that, for binary numberes
// with only one bit set - and only for such numbers -
// the bits in one less than the number are disjoint
@@ -266,14 +265,35 @@ static bool mask_is_single_axis(uint8_t axis_mask) {
return axis_mask && ((axis_mask & (axis_mask - 1)) == 0);
}
static bool axis_is_squared(uint8_t axis_mask) {
static AxisMask squaredAxes() {
AxisMask mask = 0;
auto axes = config->_axes;
auto n_axis = axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
auto homing = axes->_axis[axis]->_homing;
if (homing && homing->_square) {
mask |= bit(axis);
}
}
return mask;
}
static bool axis_is_squared(AxisMask axis_mask) {
// Squaring can only be done if it is the only axis in the mask
if (axis_mask & homing_squared_axes->get()) {
// cases:
// axis_mask has one bit:
// axis is squared: return true
// else: return false
// else:
// one of the axes is squared: message and return false
// else return false
if (axis_mask & squaredAxes()) {
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;
@@ -298,19 +318,39 @@ static bool axis_is_squared(uint8_t axis_mask) {
# define RESTORE_STEPPER(save_stepper)
#endif
// For this routine, homing_mask cannot be 0. The 0 case,
// meaning run all cycles, is handled by the caller mc_homing_cycle()
static void mc_run_one_homing_cycle(AxisMask homing_mask) {
if (axis_is_squared(homing_mask)) {
// For squaring, we first do the fast seek using both motors,
// skipping the second slow moving phase.
ganged_mode = gangDual;
limits_go_home(homing_mask, 0); // Do not do a second touch cycle
// Then we do the slow motion on the individual motors
ganged_mode = gangA;
limits_go_home(homing_mask, NHomingLocateCycle);
ganged_mode = gangB;
limits_go_home(homing_mask, NHomingLocateCycle);
ganged_mode = gangDual; // always return to dual
} else {
limits_go_home(homing_mask, NHomingLocateCycle);
}
}
// Perform homing cycle to locate and set machine zero. Only '$H' executes this command.
// NOTE: There should be no motions in the buffer and Grbl must be in an idle state before
// executing the homing cycle. This prevents incorrect buffered plans after homing.
void mc_homing_cycle(uint8_t cycle_mask) {
bool no_cycles_defined = true;
if (user_defined_homing(cycle_mask)) {
void mc_homing_cycle(AxisMask axis_mask) {
if (user_defined_homing(axis_mask)) {
return;
}
// This give kinematics a chance to do something before normal homing
// if it returns true, the homing is canceled.
if (kinematics_pre_homing(cycle_mask)) {
if (kinematics_pre_homing(axis_mask)) {
return;
}
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
@@ -326,50 +366,30 @@ void mc_homing_cycle(uint8_t cycle_mask) {
limits_disable(); // Disable hard limits pin change register for cycle duration
// -------------------------------------------------------------------------------------
// Perform homing routine. NOTE: Special motion case. Only system reset works.
n_homing_locate_cycle = NHomingLocateCycle;
#ifdef HOMING_SINGLE_AXIS_COMMANDS
/*
if (cycle_mask) { limits_go_home(cycle_mask); } // Perform homing cycle based on mask.
else
*/
if (cycle_mask) {
if (!axis_is_squared(cycle_mask)) {
limits_go_home(cycle_mask); // Homing cycle 0
} else {
ganged_mode = SquaringMode::Dual;
n_homing_locate_cycle = 0; // don't do a second touch cycle
limits_go_home(cycle_mask);
ganged_mode = SquaringMode::A;
n_homing_locate_cycle = NHomingLocateCycle; // restore to default value
limits_go_home(cycle_mask);
ganged_mode = SquaringMode::B;
limits_go_home(cycle_mask);
ganged_mode = SquaringMode::Dual; // always return to dual
}
} // Perform homing cycle based on mask.
else
#endif
{
if (axis_mask) {
mc_run_one_homing_cycle(axis_mask);
} else {
// Run all homing cycles
bool someAxisHomed = false;
for (int cycle = 0; cycle < MAX_N_AXIS; cycle++) {
auto homing_mask = homing_cycle[cycle]->get();
if (homing_mask) { // if there are some axes in this cycle
no_cycles_defined = false;
if (!axis_is_squared(homing_mask)) {
limits_go_home(homing_mask); // Homing cycle 0
} else {
ganged_mode = SquaringMode::Dual;
n_homing_locate_cycle = 0; // don't do a second touch cycle
limits_go_home(homing_mask);
ganged_mode = SquaringMode::A;
n_homing_locate_cycle = NHomingLocateCycle; // restore to default value
limits_go_home(homing_mask);
ganged_mode = SquaringMode::B;
limits_go_home(homing_mask);
ganged_mode = SquaringMode::Dual; // always return to dual
// Set axis_mask to the axes that home on this cycle
axis_mask = 0;
auto n_axis = config->_axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
auto axisConfig = config->_axes->_axis[axis];
auto homing = axisConfig->_homing;
if (homing && homing->_cycle == cycle) {
axis_mask |= bit(axis);
}
}
if (axis_mask) { // if there are some axes in this cycle
someAxisHomed = true;
mc_run_one_homing_cycle(axis_mask);
}
}
if (no_cycles_defined) {
if (!someAxisHomed) {
report_status_message(Error::HomingNoCycles, CLIENT_ALL);
}
}
@@ -412,9 +432,9 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
BACKUP_STEPPER(save_stepper);
// Initialize probing control variables
uint8_t is_probe_away = bit_istrue(parser_flags, GCParserProbeIsAway);
uint8_t is_no_error = bit_istrue(parser_flags, GCParserProbeIsNoError);
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
bool is_probe_away = bit_istrue(parser_flags, GCParserProbeIsAway);
bool is_no_error = bit_istrue(parser_flags, GCParserProbeIsNoError);
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
config->_probe->set_direction(is_probe_away);
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
// NOTE: This probe initialization error applies to all probing cycles.
@@ -476,8 +496,7 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
if (sys.abort) {
return; // Block during abort.
}
uint8_t plan_status = plan_buffer_line(parking_target, pl_data);
if (plan_status) {
if (plan_buffer_line(parking_target, pl_data)) {
sys.step_control.executeSysMotion = true;
sys.step_control.endMotion = false; // Allow parking motion to execute, if feed hold is active.
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
@@ -497,7 +516,7 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
}
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
void mc_override_ctrl_update(uint8_t override_state) {
void mc_override_ctrl_update(Override override_state) {
// Finish all queued commands before altering override control state
protocol_buffer_synchronize();
if (sys.abort) {
@@ -548,7 +567,7 @@ void mc_reset() {
}
st_go_idle(); // Force kill steppers. Position has likely been lost.
}
ganged_mode = SquaringMode::Dual; // in case an error occurred during squaring
ganged_mode = gangDual; // in case an error occurred during squaring
#ifdef USE_I2S_STEPS
if (current_stepper == ST_I2S_STREAM) {

View File

@@ -57,13 +57,13 @@ void mc_arc(float* target,
bool mc_dwell(int32_t milliseconds);
// Perform homing cycle to locate machine zero. Requires limit switches.
void mc_homing_cycle(uint8_t cycle_mask);
void mc_homing_cycle(AxisMask cycle_mask);
// Perform tool length probe cycle. Requires probe switch.
GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t parser_flags);
// Handles updating the override control state.
void mc_override_ctrl_update(uint8_t override_state);
void mc_override_ctrl_update(Override override_state);
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data);
@@ -71,10 +71,10 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data);
// Performs system reset. If in motion state, kills all motion and sets system alarm.
void mc_reset();
enum class SquaringMode : uint8_t {
Dual, // both motors run
A, // A motor runs
B, // B motor runs
};
typedef uint8_t GangMask;
const GangMask gangA = bit(0);
const GangMask gangB = bit(1);
const GangMask gangDual = gangA | gangB;
extern SquaringMode ganged_mode;
// TODO: Ideally, ganged_mode would be in the planner block instead of global
extern GangMask ganged_mode;

View File

@@ -83,7 +83,9 @@ const double INCH_PER_MM = (0.0393701);
#define bit_istrue(x, mask) ((x & mask) != 0)
#define bit_isfalse(x, mask) ((x & mask) == 0)
#define bitnum_true(x, num) (x) |= bit(num)
#define bitnum_false(x, num) (x) &= ~bit(num)
#define bitnum_istrue(x, num) ((x & bit(num)) != 0)
#define bitnum_isfalse(x, num) ((x & bit(num)) == 0)
// Read a floating point value from a string. Line points to the input buffer, char_counter
// is the indexer pointing to the current character of the line, while float_ptr is

View File

@@ -239,27 +239,29 @@ Error report_ngc(const char* value, WebUI::AuthenticationLevel auth_level, WebUI
return Error::Ok;
}
Error home(int cycle) {
if (homing_enable->get() == false) {
if (homingAxes()) {
return Error::SettingDisabled;
}
if (system_check_safety_door_ajar()) {
return Error::CheckDoor; // Block if safety door is ajar.
}
sys.state = State::Homing; // Set system state variable
#ifdef USE_I2S_STEPS
stepper_id_t save_stepper = current_stepper;
if (save_stepper == ST_I2S_STREAM) {
stepper_switch(ST_I2S_STATIC);
}
#endif
mc_homing_cycle(cycle);
#ifdef USE_I2S_STEPS
if (save_stepper == ST_I2S_STREAM && current_stepper != ST_I2S_STREAM) {
stepper_switch(ST_I2S_STREAM);
}
#else
mc_homing_cycle(cycle);
#endif
if (!sys.abort) { // Execute startup scripts after successful homing.
sys.state = State::Idle; // Set to IDLE when complete.
st_go_idle(); // Set steppers to the settings idle state before returning.

View File

@@ -98,7 +98,7 @@ bool can_park() {
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
sys.override_ctrl == Override::ParkingMotion &&
#endif
homing_enable->get() && !config->_laserMode;
homingAxes() && !config->_laserMode;
}
/*

View File

@@ -4,20 +4,8 @@ StringSetting* startup_line_0;
StringSetting* startup_line_1;
StringSetting* build_info;
AxisMaskSetting* homing_dir_mask;
AxisMaskSetting* homing_squared_axes;
FlagSetting* homing_enable;
IntSetting* status_mask;
FloatSetting* homing_feed_rate;
FloatSetting* homing_seek_rate;
FloatSetting* homing_debounce;
FloatSetting* homing_pulloff;
AxisMaskSetting* homing_cycle[MAX_N_AXIS];
FloatSetting* coolant_start_delay;
EnumSetting* spindle_type;
EnumSetting* message_level;
@@ -135,16 +123,6 @@ void make_settings() {
startup_line_1 = new StringSetting(EXTENDED, WG, "N1", "GCode/Line1", "", checkStartupLine);
// GRBL Numbered Settings
homing_pulloff = new FloatSetting(GRBL, WG, "27", "Homing/Pulloff", DEFAULT_HOMING_PULLOFF, 0, 1000);
homing_debounce = new FloatSetting(GRBL, WG, "26", "Homing/Debounce", DEFAULT_HOMING_DEBOUNCE_DELAY, 0, 10000);
homing_seek_rate = new FloatSetting(GRBL, WG, "25", "Homing/Seek", DEFAULT_HOMING_SEEK_RATE, 0, 10000);
homing_feed_rate = new FloatSetting(GRBL, WG, "24", "Homing/Feed", DEFAULT_HOMING_FEED_RATE, 0, 10000);
homing_squared_axes = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Squared", DEFAULT_HOMING_SQUARED_AXES);
homing_dir_mask = new AxisMaskSetting(GRBL, WG, "23", "Homing/DirInvert", DEFAULT_HOMING_DIR_MASK);
homing_enable = new FlagSetting(GRBL, WG, "22", "Homing/Enable", DEFAULT_HOMING_ENABLE);
build_info = new StringSetting(EXTENDED, WG, NULL, "Firmware/Build", "");
// TODO: These affect the sender communication protocol so they
@@ -154,13 +132,6 @@ void make_settings() {
status_mask = new IntSetting(GRBL, WG, "10", "Report/Status", DEFAULT_STATUS_REPORT_MASK, 0, 3);
homing_cycle[5] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle5", DEFAULT_HOMING_CYCLE_5);
homing_cycle[4] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle4", DEFAULT_HOMING_CYCLE_4);
homing_cycle[3] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle3", DEFAULT_HOMING_CYCLE_3);
homing_cycle[2] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle2", DEFAULT_HOMING_CYCLE_2);
homing_cycle[1] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle1", DEFAULT_HOMING_CYCLE_1);
homing_cycle[0] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle0", DEFAULT_HOMING_CYCLE_0);
user_macro3 = new StringSetting(EXTENDED, WG, NULL, "User/Macro3", DEFAULT_USER_MACRO3);
user_macro2 = new StringSetting(EXTENDED, WG, NULL, "User/Macro2", DEFAULT_USER_MACRO2);
user_macro1 = new StringSetting(EXTENDED, WG, NULL, "User/Macro1", DEFAULT_USER_MACRO1);

View File

@@ -4,19 +4,8 @@ extern StringSetting* startup_line_0;
extern StringSetting* startup_line_1;
extern StringSetting* build_info;
extern AxisMaskSetting* homing_dir_mask;
extern AxisMaskSetting* homing_squared_axes;
extern AxisMaskSetting* homing_cycle[MAX_N_AXIS];
extern FlagSetting* homing_enable;
extern IntSetting* status_mask;
extern FloatSetting* homing_feed_rate;
extern FloatSetting* homing_seek_rate;
extern FloatSetting* homing_debounce;
extern FloatSetting* homing_pulloff;
extern EnumSetting* spindle_type;
extern StringSetting* user_macro0;