Merge pull request #1661 from thinkyhead/G92_no_offset
Don't add home offsets in G29
This commit is contained in:
commit
8bd6e37b21
@ -18,7 +18,7 @@
|
||||
* max_xy_jerk
|
||||
* max_z_jerk
|
||||
* max_e_jerk
|
||||
* add_homing (x3)
|
||||
* home_offset (x3)
|
||||
*
|
||||
* Mesh bed leveling:
|
||||
* active
|
||||
@ -136,7 +136,7 @@ void Config_StoreSettings() {
|
||||
EEPROM_WRITE_VAR(i, max_xy_jerk);
|
||||
EEPROM_WRITE_VAR(i, max_z_jerk);
|
||||
EEPROM_WRITE_VAR(i, max_e_jerk);
|
||||
EEPROM_WRITE_VAR(i, add_homing);
|
||||
EEPROM_WRITE_VAR(i, home_offset);
|
||||
|
||||
uint8_t mesh_num_x = 3;
|
||||
uint8_t mesh_num_y = 3;
|
||||
@ -294,7 +294,7 @@ void Config_RetrieveSettings() {
|
||||
EEPROM_READ_VAR(i, max_xy_jerk);
|
||||
EEPROM_READ_VAR(i, max_z_jerk);
|
||||
EEPROM_READ_VAR(i, max_e_jerk);
|
||||
EEPROM_READ_VAR(i, add_homing);
|
||||
EEPROM_READ_VAR(i, home_offset);
|
||||
|
||||
uint8_t mesh_num_x = 0;
|
||||
uint8_t mesh_num_y = 0;
|
||||
@ -447,7 +447,7 @@ void Config_ResetDefault() {
|
||||
max_xy_jerk = DEFAULT_XYJERK;
|
||||
max_z_jerk = DEFAULT_ZJERK;
|
||||
max_e_jerk = DEFAULT_EJERK;
|
||||
add_homing[X_AXIS] = add_homing[Y_AXIS] = add_homing[Z_AXIS] = 0;
|
||||
home_offset[X_AXIS] = home_offset[Y_AXIS] = home_offset[Z_AXIS] = 0;
|
||||
|
||||
#if defined(MESH_BED_LEVELING)
|
||||
mbl.active = 0;
|
||||
@ -607,9 +607,9 @@ void Config_PrintSettings(bool forReplay) {
|
||||
SERIAL_ECHOLNPGM("Home offset (mm):");
|
||||
SERIAL_ECHO_START;
|
||||
}
|
||||
SERIAL_ECHOPAIR(" M206 X", add_homing[X_AXIS] );
|
||||
SERIAL_ECHOPAIR(" Y", add_homing[Y_AXIS] );
|
||||
SERIAL_ECHOPAIR(" Z", add_homing[Z_AXIS] );
|
||||
SERIAL_ECHOPAIR(" M206 X", home_offset[X_AXIS] );
|
||||
SERIAL_ECHOPAIR(" Y", home_offset[Y_AXIS] );
|
||||
SERIAL_ECHOPAIR(" Z", home_offset[Z_AXIS] );
|
||||
SERIAL_EOL;
|
||||
|
||||
#ifdef DELTA
|
||||
|
@ -240,7 +240,7 @@ extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in per
|
||||
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
|
||||
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
|
||||
extern float current_position[NUM_AXIS] ;
|
||||
extern float add_homing[3];
|
||||
extern float home_offset[3];
|
||||
#ifdef DELTA
|
||||
extern float endstop_adj[3];
|
||||
extern float delta_radius;
|
||||
|
@ -248,7 +248,7 @@ float volumetric_multiplier[EXTRUDERS] = {1.0
|
||||
#endif
|
||||
};
|
||||
float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
|
||||
float add_homing[3] = { 0, 0, 0 };
|
||||
float home_offset[3] = { 0, 0, 0 };
|
||||
#ifdef DELTA
|
||||
float endstop_adj[3] = { 0, 0, 0 };
|
||||
#endif
|
||||
@ -984,7 +984,7 @@ static int dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
|
||||
|
||||
static float x_home_pos(int extruder) {
|
||||
if (extruder == 0)
|
||||
return base_home_pos(X_AXIS) + add_homing[X_AXIS];
|
||||
return base_home_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
else
|
||||
// In dual carriage mode the extruder offset provides an override of the
|
||||
// second X-carriage offset when homed - otherwise X2_HOME_POS is used.
|
||||
@ -1016,9 +1016,9 @@ static void axis_is_at_home(int axis) {
|
||||
return;
|
||||
}
|
||||
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
|
||||
current_position[X_AXIS] = base_home_pos(X_AXIS) + add_homing[X_AXIS];
|
||||
min_pos[X_AXIS] = base_min_pos(X_AXIS) + add_homing[X_AXIS];
|
||||
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + add_homing[X_AXIS],
|
||||
current_position[X_AXIS] = base_home_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
min_pos[X_AXIS] = base_min_pos(X_AXIS) + home_offset[X_AXIS];
|
||||
max_pos[X_AXIS] = min(base_max_pos(X_AXIS) + home_offset[X_AXIS],
|
||||
max(extruder_offset[X_AXIS][1], X2_MAX_POS) - duplicate_extruder_x_offset);
|
||||
return;
|
||||
}
|
||||
@ -1046,11 +1046,11 @@ static void axis_is_at_home(int axis) {
|
||||
|
||||
for (i=0; i<2; i++)
|
||||
{
|
||||
delta[i] -= add_homing[i];
|
||||
delta[i] -= home_offset[i];
|
||||
}
|
||||
|
||||
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(add_homing[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(add_homing[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
|
||||
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
|
||||
|
||||
@ -1068,14 +1068,14 @@ static void axis_is_at_home(int axis) {
|
||||
}
|
||||
else
|
||||
{
|
||||
current_position[axis] = base_home_pos(axis) + add_homing[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + add_homing[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + add_homing[axis];
|
||||
current_position[axis] = base_home_pos(axis) + home_offset[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
|
||||
}
|
||||
#else
|
||||
current_position[axis] = base_home_pos(axis) + add_homing[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + add_homing[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + add_homing[axis];
|
||||
current_position[axis] = base_home_pos(axis) + home_offset[axis];
|
||||
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
|
||||
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -1858,7 +1858,7 @@ inline void gcode_G28() {
|
||||
if (code_value_long() != 0) {
|
||||
current_position[X_AXIS] = code_value()
|
||||
#ifndef SCARA
|
||||
+ add_homing[X_AXIS]
|
||||
+ home_offset[X_AXIS]
|
||||
#endif
|
||||
;
|
||||
}
|
||||
@ -1867,7 +1867,7 @@ inline void gcode_G28() {
|
||||
if (code_seen(axis_codes[Y_AXIS]) && code_value_long() != 0) {
|
||||
current_position[Y_AXIS] = code_value()
|
||||
#ifndef SCARA
|
||||
+ add_homing[Y_AXIS]
|
||||
+ home_offset[Y_AXIS]
|
||||
#endif
|
||||
;
|
||||
}
|
||||
@ -1941,7 +1941,7 @@ inline void gcode_G28() {
|
||||
|
||||
|
||||
if (code_seen(axis_codes[Z_AXIS]) && code_value_long() != 0)
|
||||
current_position[Z_AXIS] = code_value() + add_homing[Z_AXIS];
|
||||
current_position[Z_AXIS] = code_value() + home_offset[Z_AXIS];
|
||||
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
if (home_all_axis || code_seen(axis_codes[Z_AXIS]))
|
||||
@ -2512,24 +2512,15 @@ inline void gcode_G92() {
|
||||
if (!code_seen(axis_codes[E_AXIS]))
|
||||
st_synchronize();
|
||||
|
||||
for (int i=0;i<NUM_AXIS;i++) {
|
||||
for (int i = 0; i < NUM_AXIS; i++) {
|
||||
if (code_seen(axis_codes[i])) {
|
||||
if (i == E_AXIS) {
|
||||
current_position[i] = code_value();
|
||||
if (i == E_AXIS)
|
||||
plan_set_e_position(current_position[E_AXIS]);
|
||||
}
|
||||
else {
|
||||
current_position[i] = code_value() +
|
||||
#ifdef SCARA
|
||||
((i != X_AXIS && i != Y_AXIS) ? add_homing[i] : 0)
|
||||
#else
|
||||
add_homing[i]
|
||||
#endif
|
||||
;
|
||||
else
|
||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
@ -3464,9 +3455,9 @@ inline void gcode_M114() {
|
||||
SERIAL_PROTOCOLLN("");
|
||||
|
||||
SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
|
||||
SERIAL_PROTOCOL(delta[X_AXIS]+add_homing[X_AXIS]);
|
||||
SERIAL_PROTOCOL(delta[X_AXIS]+home_offset[X_AXIS]);
|
||||
SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
|
||||
SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homing[Y_AXIS]);
|
||||
SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+home_offset[Y_AXIS]);
|
||||
SERIAL_PROTOCOLLN("");
|
||||
|
||||
SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
|
||||
@ -3684,12 +3675,12 @@ inline void gcode_M205() {
|
||||
inline void gcode_M206() {
|
||||
for (int8_t i=X_AXIS; i <= Z_AXIS; i++) {
|
||||
if (code_seen(axis_codes[i])) {
|
||||
add_homing[i] = code_value();
|
||||
home_offset[i] = code_value();
|
||||
}
|
||||
}
|
||||
#ifdef SCARA
|
||||
if (code_seen('T')) add_homing[X_AXIS] = code_value(); // Theta
|
||||
if (code_seen('P')) add_homing[Y_AXIS] = code_value(); // Psi
|
||||
if (code_seen('T')) home_offset[X_AXIS] = code_value(); // Theta
|
||||
if (code_seen('P')) home_offset[Y_AXIS] = code_value(); // Psi
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -5287,7 +5278,7 @@ void clamp_to_software_endstops(float target[3])
|
||||
float negative_z_offset = 0;
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
if (Z_PROBE_OFFSET_FROM_EXTRUDER < 0) negative_z_offset = negative_z_offset + Z_PROBE_OFFSET_FROM_EXTRUDER;
|
||||
if (add_homing[Z_AXIS] < 0) negative_z_offset = negative_z_offset + add_homing[Z_AXIS];
|
||||
if (home_offset[Z_AXIS] < 0) negative_z_offset = negative_z_offset + home_offset[Z_AXIS];
|
||||
#endif
|
||||
|
||||
if (target[Z_AXIS] < min_pos[Z_AXIS]+negative_z_offset) target[Z_AXIS] = min_pos[Z_AXIS]+negative_z_offset;
|
||||
|
@ -437,7 +437,7 @@ static void lcd_main_menu() {
|
||||
void lcd_set_home_offsets() {
|
||||
for(int8_t i=0; i < NUM_AXIS; i++) {
|
||||
if (i != E_AXIS) {
|
||||
add_homing[i] -= current_position[i];
|
||||
home_offset[i] -= current_position[i];
|
||||
current_position[i] = 0.0;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user