Move some Stepper methods to Planner (#10719)

This commit is contained in:
Scott Lahteine 2018-05-12 09:29:17 -05:00 committed by GitHub
parent 8c81e6341a
commit ea353c3df6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
12 changed files with 139 additions and 136 deletions

View File

@ -264,7 +264,7 @@
#endif
G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
set_destination_from_current();
stepper.synchronize(); // Without this synchronize, the purge is more consistent,
planner.synchronize(); // Without this synchronize, the purge is more consistent,
// but because the planner has a buffer, we won't be able
// to stop as quickly. So we put up with the less smooth
// action to give the user a more responsive 'Stop'.

View File

@ -99,7 +99,7 @@
//the encoder likely lost its place when the error occured, so we'll reset and use the printer's
//idea of where it the axis is to re-initialise
float position = stepper.get_axis_position_mm(encoderAxis);
float position = planner.get_axis_position_mm(encoderAxis);
int32_t positionInTicks = position * get_ticks_unit();
//shift position from previous to current position
@ -254,7 +254,7 @@
float I2CPositionEncoder::get_axis_error_mm(const bool report) {
float target, actual, error;
target = stepper.get_axis_position_mm(encoderAxis);
target = planner.get_axis_position_mm(encoderAxis);
actual = mm_from_count(position);
error = actual - target;
@ -349,18 +349,18 @@
ec = false;
LOOP_NA(i) {
startCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
endCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
startCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
endCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
}
startCoord[encoderAxis] = startPosition;
endCoord[encoderAxis] = endPosition;
stepper.synchronize();
planner.synchronize();
planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
// if the module isn't currently trusted, wait until it is (or until it should be if things are working)
if (!trusted) {
@ -371,8 +371,8 @@
if (trusted) { // if trusted, commence test
planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
}
return trusted;
@ -408,19 +408,19 @@
travelDistance = endDistance - startDistance;
LOOP_NA(i) {
startCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
endCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
startCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
endCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
}
startCoord[encoderAxis] = startDistance;
endCoord[encoderAxis] = endDistance;
stepper.synchronize();
planner.synchronize();
LOOP_L_N(i, iter) {
planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
delay(250);
startCount = get_position();
@ -428,8 +428,8 @@
//do_blocking_move_to(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS]);
planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
//Read encoder distance
delay(250);

View File

@ -1713,7 +1713,7 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f
#endif
stepper.synchronize();
planner.synchronize();
feedrate_mm_s = old_feedrate_mm_s;
@ -2984,7 +2984,7 @@ static void do_homing_move(const AxisEnum axis, const float distance, const floa
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder);
#endif
stepper.synchronize();
planner.synchronize();
if (is_home_dir) {
@ -3355,7 +3355,7 @@ inline void gcode_G0_G1(
#define _MOVE_SYNC parser.seenval('Z') // Only for Z move
#endif
if (_MOVE_SYNC) {
stepper.synchronize();
planner.synchronize();
SERIAL_ECHOLNPGM(MSG_Z_MOVE_COMP);
}
#endif
@ -3470,7 +3470,7 @@ inline void gcode_G4() {
if (parser.seenval('P')) dwell_ms = parser.value_millis(); // milliseconds to wait
if (parser.seenval('S')) dwell_ms = parser.value_millis_from_seconds(); // seconds to wait
stepper.synchronize();
planner.synchronize();
#if ENABLED(NANODLP_Z_SYNC)
SERIAL_ECHOLNPGM(MSG_Z_MOVE_COMP);
#endif
@ -3797,9 +3797,9 @@ inline void gcode_G4() {
#endif
#if ABL_PLANAR
const float diff[XYZ] = {
stepper.get_axis_position_mm(X_AXIS) - current_position[X_AXIS],
stepper.get_axis_position_mm(Y_AXIS) - current_position[Y_AXIS],
stepper.get_axis_position_mm(Z_AXIS) - current_position[Z_AXIS]
planner.get_axis_position_mm(X_AXIS) - current_position[X_AXIS],
planner.get_axis_position_mm(Y_AXIS) - current_position[Y_AXIS],
planner.get_axis_position_mm(Z_AXIS) - current_position[Z_AXIS]
};
SERIAL_ECHOPGM("ABL Adjustment X");
if (diff[X_AXIS] > 0) SERIAL_CHAR('+');
@ -3892,7 +3892,7 @@ inline void gcode_G4() {
current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (delta_height + 10);
feedrate_mm_s = homing_feedrate(X_AXIS);
buffer_line_to_current_position();
stepper.synchronize();
planner.synchronize();
// Re-enable stealthChop if used. Disable diag1 pin on driver.
#if ENABLED(SENSORLESS_HOMING)
@ -4036,7 +4036,7 @@ inline void gcode_G28(const bool always_home_all) {
#endif
// Wait for planner moves to finish!
stepper.synchronize();
planner.synchronize();
// Cancel the active G29 session
#if ENABLED(PROBE_MANUALLY)
@ -4350,7 +4350,7 @@ void home_all_axes() { gcode_G28(true); }
// One last "return to the bed" (as originally coded) at completion
current_position[Z_AXIS] = MANUAL_PROBE_HEIGHT;
buffer_line_to_current_position();
stepper.synchronize();
planner.synchronize();
// After recording the last point, activate home and activate
mbl_probe_index = -1;
@ -4365,7 +4365,7 @@ void home_all_axes() { gcode_G28(true); }
current_position[Z_AXIS] = 0;
set_destination_from_current();
buffer_line_to_destination(homing_feedrate(Z_AXIS));
stepper.synchronize();
planner.synchronize();
#endif
#if ENABLED(LCD_BED_LEVELING)
@ -4775,7 +4775,7 @@ void home_all_axes() { gcode_G28(true); }
SERIAL_EOL();
}
stepper.synchronize();
planner.synchronize();
// Disable auto bed leveling during G29.
// Be formal so G29 can be done successively without G28.
@ -5333,7 +5333,7 @@ void home_all_axes() { gcode_G28(true); }
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT);
#endif
stepper.synchronize();
planner.synchronize();
enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
#endif
@ -5464,7 +5464,7 @@ void home_all_axes() { gcode_G28(true); }
tool_change(0, 0, true);
#endif
stepper.synchronize();
planner.synchronize();
setup_for_endstop_or_probe_move();
#if HAS_LEVELING
@ -6131,12 +6131,12 @@ void home_all_axes() { gcode_G28(true); }
#endif
// Move until destination reached or target hit
stepper.synchronize();
planner.synchronize();
endstops.enable(true);
G38_move = true;
G38_endstop_hit = false;
prepare_move_to_destination();
stepper.synchronize();
planner.synchronize();
G38_move = false;
endstops.hit_on_purpose();
@ -6159,11 +6159,11 @@ void home_all_axes() { gcode_G28(true); }
// Bump the target more slowly
LOOP_XYZ(i) destination[i] -= retract_mm[i] * 2;
stepper.synchronize();
planner.synchronize();
endstops.enable(true);
G38_move = true;
prepare_move_to_destination();
stepper.synchronize();
planner.synchronize();
G38_move = false;
set_current_from_steppers_for_axis(ALL_AXES);
@ -6341,7 +6341,7 @@ inline void gcode_G92() {
const bool has_message = !hasP && !hasS && args && *args;
stepper.synchronize();
planner.synchronize();
#if ENABLED(ULTIPANEL)
@ -6442,7 +6442,7 @@ inline void gcode_G92() {
inline void gcode_M3_M4(bool is_M3) {
stepper.synchronize(); // wait until previous movement commands (G0/G0/G2/G3) have completed before playing with the spindle
planner.synchronize(); // wait until previous movement commands (G0/G0/G2/G3) have completed before playing with the spindle
#if SPINDLE_DIR_CHANGE
const bool rotation_dir = (is_M3 && !SPINDLE_INVERT_DIR || !is_M3 && SPINDLE_INVERT_DIR) ? HIGH : LOW;
if (SPINDLE_STOP_ON_DIR_CHANGE \
@ -6492,7 +6492,7 @@ inline void gcode_G92() {
* M5 turn off spindle
*/
inline void gcode_M5() {
stepper.synchronize();
planner.synchronize();
WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);
#if ENABLED(SPINDLE_LASER_PWM)
analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);
@ -6517,7 +6517,7 @@ inline void gcode_M17() {
destination[E_AXIS] += length / planner.e_factor[active_extruder];
planner.buffer_line_kinematic(destination, fr, active_extruder);
set_current_from_destination();
stepper.synchronize();
planner.synchronize();
}
static float resume_position[XYZE];
@ -6809,7 +6809,7 @@ inline void gcode_M17() {
COPY(resume_position, current_position);
// Wait for synchronize steppers
stepper.synchronize();
planner.synchronize();
// Initial retract before move to filament change position
if (retract && thermalManager.hotEnoughToExtrude(active_extruder))
@ -7141,7 +7141,7 @@ inline void gcode_M31() {
*
*/
inline void gcode_M32() {
if (card.sdprinting) stepper.synchronize();
if (card.sdprinting) planner.synchronize();
if (card.cardOK) {
const bool call_procedure = parser.boolval('P');
@ -8533,7 +8533,7 @@ inline void gcode_M18_M84() {
stepper.finish_and_disable();
}
else {
stepper.synchronize();
planner.synchronize();
if (parser.seen('X')) disable_X();
if (parser.seen('Y')) disable_Y();
if (parser.seen('Z')) disable_Z();
@ -8612,8 +8612,8 @@ void report_current_position() {
stepper.report_positions();
#if IS_SCARA
SERIAL_PROTOCOLPAIR("SCARA Theta:", stepper.get_axis_position_degrees(A_AXIS));
SERIAL_PROTOCOLLNPAIR(" Psi+Theta:", stepper.get_axis_position_degrees(B_AXIS));
SERIAL_PROTOCOLPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS));
SERIAL_PROTOCOLLNPAIR(" Psi+Theta:", planner.get_axis_position_degrees(B_AXIS));
SERIAL_EOL();
#endif
}
@ -8669,7 +8669,7 @@ void report_current_position() {
report_xyz(delta);
#endif
stepper.synchronize();
planner.synchronize();
SERIAL_PROTOCOLPGM("Stepper:");
LOOP_XYZE(i) {
@ -8682,8 +8682,8 @@ void report_current_position() {
#if IS_SCARA
const float deg[XYZ] = {
stepper.get_axis_position_degrees(A_AXIS),
stepper.get_axis_position_degrees(B_AXIS)
planner.get_axis_position_degrees(A_AXIS),
planner.get_axis_position_degrees(B_AXIS)
};
SERIAL_PROTOCOLPGM("Degrees:");
report_xyze(deg, 2);
@ -8691,7 +8691,7 @@ void report_current_position() {
SERIAL_PROTOCOLPGM("FromStp:");
get_cartesian_from_steppers(); // writes cartes[XYZ] (with forward kinematics)
const float from_steppers[XYZE] = { cartes[X_AXIS], cartes[Y_AXIS], cartes[Z_AXIS], stepper.get_axis_position_mm(E_AXIS) };
const float from_steppers[XYZE] = { cartes[X_AXIS], cartes[Y_AXIS], cartes[Z_AXIS], planner.get_axis_position_mm(E_AXIS) };
report_xyze(from_steppers);
const float diff[XYZE] = {
@ -8717,7 +8717,7 @@ inline void gcode_M114() {
}
#endif
stepper.synchronize();
planner.synchronize();
report_current_position();
}
@ -9429,7 +9429,7 @@ inline void gcode_M226() {
int target = LOW;
stepper.synchronize();
planner.synchronize();
pinMode(pin, INPUT);
switch (pin_state) {
@ -9893,7 +9893,7 @@ inline void gcode_M303() {
/**
* M400: Finish all moves
*/
inline void gcode_M400() { stepper.synchronize(); }
inline void gcode_M400() { planner.synchronize(); }
#if HAS_BED_PROBE
@ -9977,7 +9977,7 @@ inline void gcode_M400() { stepper.synchronize(); }
void quickstop_stepper() {
stepper.quick_stop();
stepper.synchronize();
planner.synchronize();
set_current_from_steppers_for_axis(ALL_AXES);
SYNC_PLAN_POSITION_KINEMATIC();
}
@ -10588,7 +10588,7 @@ inline void gcode_M502() {
#if ENABLED(MK2_MULTIPLEXER)
inline void select_multiplexed_stepper(const uint8_t e) {
stepper.synchronize();
planner.synchronize();
disable_e_steppers();
WRITE(E_MUX0_PIN, TEST(e, 0) ? HIGH : LOW);
WRITE(E_MUX1_PIN, TEST(e, 1) ? HIGH : LOW);
@ -10613,7 +10613,7 @@ inline void gcode_M502() {
* Note: the X axis should be homed after changing dual x-carriage mode.
*/
inline void gcode_M605() {
stepper.synchronize();
planner.synchronize();
if (parser.seen('S')) dual_x_carriage_mode = (DualXMode)parser.value_byte();
switch (dual_x_carriage_mode) {
case DXC_FULL_CONTROL_MODE:
@ -10645,7 +10645,7 @@ inline void gcode_M502() {
#elif ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
inline void gcode_M605() {
stepper.synchronize();
planner.synchronize();
extruder_duplication_enabled = parser.intval('S') == (int)DXC_DUPLICATION_MODE;
SERIAL_ECHO_START();
SERIAL_ECHOLNPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF);
@ -10799,7 +10799,7 @@ inline void gcode_M502() {
if (parser.seenval('K')) {
const float newK = parser.floatval('K');
if (WITHIN(newK, 0, 10)) {
stepper.synchronize();
planner.synchronize();
planner.extruder_advance_K = newK;
}
else
@ -11531,7 +11531,7 @@ inline void gcode_M999() {
inline void move_extruder_servo(const uint8_t e) {
constexpr int16_t angles[] = SWITCHING_EXTRUDER_SERVO_ANGLES;
static_assert(COUNT(angles) == REQ_ANGLES, "SWITCHING_EXTRUDER_SERVO_ANGLES needs " STRINGIFY(REQ_ANGLES) " angles.");
stepper.synchronize();
planner.synchronize();
#if EXTRUDERS & 1
if (e < EXTRUDERS - 1)
#endif
@ -11545,7 +11545,7 @@ inline void gcode_M999() {
#if ENABLED(SWITCHING_NOZZLE)
inline void move_nozzle_servo(const uint8_t e) {
const int16_t angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES;
stepper.synchronize();
planner.synchronize();
MOVE_SERVO(SWITCHING_NOZZLE_SERVO_NR, angles[e]);
safe_delay(500);
}
@ -11664,7 +11664,7 @@ inline void invalid_extruder_error(const uint8_t e) {
planner.max_feedrate_mm_s[i == 1 ? X_AXIS : Z_AXIS],
active_extruder
);
stepper.synchronize();
planner.synchronize();
}
// Apply Y & Z extruder offset (X offset is used as home pos with Dual X)
@ -11762,7 +11762,7 @@ inline void invalid_extruder_error(const uint8_t e) {
if (DEBUGGING(LEVELING)) DEBUG_POS("Moving to Raised Z-Position", current_position);
#endif
planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[Z_AXIS], active_extruder);
stepper.synchronize();
planner.synchronize();
// STEP 2
current_position[X_AXIS] = parkingposx[active_extruder] + hotend_offset[X_AXIS][active_extruder];
@ -11771,7 +11771,7 @@ inline void invalid_extruder_error(const uint8_t e) {
if (DEBUGGING(LEVELING)) DEBUG_POS("Moving ParkPos", current_position);
#endif
planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder);
stepper.synchronize();
planner.synchronize();
// STEP 3
#if ENABLED(DEBUG_LEVELING_FEATURE)
@ -11789,7 +11789,7 @@ inline void invalid_extruder_error(const uint8_t e) {
if (DEBUGGING(LEVELING)) DEBUG_POS("Moving away from parked extruder", current_position);
#endif
planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder);
stepper.synchronize();
planner.synchronize();
// STEP 5
#if ENABLED(DEBUG_LEVELING_FEATURE)
@ -11810,7 +11810,7 @@ inline void invalid_extruder_error(const uint8_t e) {
if (DEBUGGING(LEVELING)) DEBUG_POS("Move UnparkPos", current_position);
#endif
planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS]/2, active_extruder);
stepper.synchronize();
planner.synchronize();
// Step 7
current_position[X_AXIS] = midpos - hotend_offset[X_AXIS][tmp_extruder];
@ -11819,7 +11819,7 @@ inline void invalid_extruder_error(const uint8_t e) {
if (DEBUGGING(LEVELING)) DEBUG_POS("Move midway to new extruder", current_position);
#endif
planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder);
stepper.synchronize();
planner.synchronize();
#if ENABLED(DEBUG_LEVELING_FEATURE)
SERIAL_ECHOLNPGM("Autopark done.");
#endif
@ -11956,7 +11956,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
#endif
} // (tmp_extruder != active_extruder)
stepper.synchronize();
planner.synchronize();
#if ENABLED(EXT_SOLENOID) && !ENABLED(PARKING_EXTRUDER)
disable_all_solenoids();
@ -11983,7 +11983,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
#endif // HOTENDS <= 1
#if DO_SWITCH_EXTRUDER
stepper.synchronize();
planner.synchronize();
move_extruder_servo(active_extruder);
#endif
@ -12903,21 +12903,21 @@ void ok_to_send() {
void get_cartesian_from_steppers() {
#if ENABLED(DELTA)
forward_kinematics_DELTA(
stepper.get_axis_position_mm(A_AXIS),
stepper.get_axis_position_mm(B_AXIS),
stepper.get_axis_position_mm(C_AXIS)
planner.get_axis_position_mm(A_AXIS),
planner.get_axis_position_mm(B_AXIS),
planner.get_axis_position_mm(C_AXIS)
);
#else
#if IS_SCARA
forward_kinematics_SCARA(
stepper.get_axis_position_degrees(A_AXIS),
stepper.get_axis_position_degrees(B_AXIS)
planner.get_axis_position_degrees(A_AXIS),
planner.get_axis_position_degrees(B_AXIS)
);
#else
cartes[X_AXIS] = stepper.get_axis_position_mm(X_AXIS);
cartes[Y_AXIS] = stepper.get_axis_position_mm(Y_AXIS);
cartes[X_AXIS] = planner.get_axis_position_mm(X_AXIS);
cartes[Y_AXIS] = planner.get_axis_position_mm(Y_AXIS);
#endif
cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
cartes[Z_AXIS] = planner.get_axis_position_mm(Z_AXIS);
#endif
}
@ -13432,7 +13432,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS],
planner.max_feedrate_mm_s[X_AXIS], 1
);
stepper.synchronize();
planner.synchronize();
SYNC_PLAN_POSITION_KINEMATIC();
extruder_duplication_enabled = true;
active_extruder_parked = false;
@ -14043,7 +14043,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
current_position[E_AXIS] = olde;
planner.set_e_position_mm(olde);
stepper.synchronize();
planner.synchronize();
#if ENABLED(SWITCHING_EXTRUDER)
E0_ENABLE_WRITE(oldstatus);
#else

View File

@ -921,7 +921,7 @@ uint16_t CardReader::get_num_Files() {
}
void CardReader::printingHasFinished() {
stepper.synchronize();
planner.synchronize();
file.close();
if (file_subcall_ctr > 0) { // Heading up to a parent file that called current as a procedure.
file_subcall_ctr--;

View File

@ -1275,6 +1275,42 @@ void Planner::check_axes_activity() {
#endif // PLANNER_LEVELING
/**
* Get an axis position according to stepper position(s)
* For CORE machines apply translation from ABC to XYZ.
*/
float Planner::get_axis_position_mm(const AxisEnum axis) {
float axis_steps;
#if IS_CORE
// Requesting one of the "core" axes?
if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) {
// Protect the access to the position.
const bool was_enabled = STEPPER_ISR_ENABLED();
DISABLE_STEPPER_DRIVER_INTERRUPT();
// ((a1+a2)+(a1-a2))/2 -> (a1+a2+a1-a2)/2 -> (a1+a1)/2 -> a1
// ((a1+a2)-(a1-a2))/2 -> (a1+a2-a1+a2)/2 -> (a2+a2)/2 -> a2
axis_steps = 0.5f * (
axis == CORE_AXIS_2 ? CORESIGN(stepper.position(CORE_AXIS_1) - stepper.position(CORE_AXIS_2))
: stepper.position(CORE_AXIS_1) + stepper.position(CORE_AXIS_2)
);
if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT();
}
else
axis_steps = stepper.position(axis);
#else
axis_steps = stepper.position(axis);
#endif
return axis_steps * steps_to_mm[axis];
}
/**
* Block until all buffered steps are executed / cleaned
*/
void Planner::synchronize() { while (has_blocks_queued() || stepper.cleaning_buffer_counter) idle(); }
/**
* Planner::_buffer_steps
*

View File

@ -542,11 +542,27 @@ class Planner {
*/
static void sync_from_steppers();
/**
* Get an axis position according to stepper position(s)
* For CORE machines apply translation from ABC to XYZ.
*/
static float get_axis_position_mm(const AxisEnum axis);
// SCARA AB axes are in degrees, not mm
#if IS_SCARA
FORCE_INLINE static float get_axis_position_degrees(const AxisEnum axis) { return get_axis_position_mm(axis); }
#endif
/**
* Does the buffer have any blocks queued?
*/
FORCE_INLINE static bool has_blocks_queued() { return (block_buffer_head != block_buffer_tail); }
//
// Block until all buffered steps are executed
//
static void synchronize();
/**
* "Discard" the block and "release" the memory.
* Called when the current block is no longer needed.

View File

@ -48,7 +48,7 @@ class FilamentRunoutSensor {
if ((IS_SD_PRINTING || print_job_timer.isRunning()) && check() && !filament_ran_out) {
filament_ran_out = true;
enqueue_and_echo_commands_P(PSTR(FILAMENT_RUNOUT_SCRIPT));
stepper.synchronize();
planner.synchronize();
}
}
private:

View File

@ -1950,12 +1950,6 @@ void Stepper::init() {
set_directions(); // Init directions to last_direction_bits = 0
}
/**
* Block until all buffered steps are executed / cleaned
*/
void Stepper::synchronize() { while (planner.has_blocks_queued() || cleaning_buffer_counter) idle(); }
/**
* Set the stepper positions directly in steps
*
@ -2001,34 +1995,8 @@ int32_t Stepper::position(const AxisEnum axis) {
return count_pos;
}
/**
* Get an axis position according to stepper position(s)
* For CORE machines apply translation from ABC to XYZ.
*/
float Stepper::get_axis_position_mm(const AxisEnum axis) {
float axis_steps;
#if IS_CORE
// Requesting one of the "core" axes?
if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) {
CRITICAL_SECTION_START;
// ((a1+a2)+(a1-a2))/2 -> (a1+a2+a1-a2)/2 -> (a1+a1)/2 -> a1
// ((a1+a2)-(a1-a2))/2 -> (a1+a2-a1+a2)/2 -> (a2+a2)/2 -> a2
axis_steps = 0.5f * (
axis == CORE_AXIS_2 ? CORESIGN(count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2])
: count_position[CORE_AXIS_1] + count_position[CORE_AXIS_2]
);
CRITICAL_SECTION_END;
}
else
axis_steps = position(axis);
#else
axis_steps = position(axis);
#endif
return axis_steps * planner.steps_to_mm[axis];
}
void Stepper::finish_and_disable() {
synchronize();
planner.synchronize();
disable_all_steppers();
}

View File

@ -207,11 +207,6 @@ class Stepper {
static void advance_isr_scheduler();
#endif
//
// Block until all buffered steps are executed
//
static void synchronize();
//
// Set the current position in steps
//
@ -220,14 +215,14 @@ class Stepper {
FORCE_INLINE static void _set_position(const AxisEnum a, const int32_t &v) { count_position[a] = v; }
FORCE_INLINE static void set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) {
synchronize();
planner.synchronize();
CRITICAL_SECTION_START;
_set_position(a, b, c, e);
CRITICAL_SECTION_END;
}
static void set_position(const AxisEnum a, const int32_t &v) {
synchronize();
planner.synchronize();
CRITICAL_SECTION_START;
count_position[a] = v;
CRITICAL_SECTION_END;
@ -236,7 +231,7 @@ class Stepper {
FORCE_INLINE static void _set_e_position(const int32_t &e) { count_position[E_AXIS] = e; }
static void set_e_position(const int32_t &e) {
synchronize();
planner.synchronize();
CRITICAL_SECTION_START;
count_position[E_AXIS] = e;
CRITICAL_SECTION_END;
@ -257,18 +252,6 @@ class Stepper {
//
static void report_positions();
//
// Get the position (mm) of an axis based on stepper position(s)
//
static float get_axis_position_mm(const AxisEnum axis);
//
// SCARA AB axes are in degrees, not mm
//
#if IS_SCARA
FORCE_INLINE static float get_axis_position_degrees(const AxisEnum axis) { return get_axis_position_mm(axis); }
#endif
//
// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
// to notify the subsystem that it is time to go to work.

View File

@ -792,7 +792,7 @@
do_blocking_move_to(0.5 * (MESH_MAX_X - (MESH_MIN_X)), 0.5 * (MESH_MAX_Y - (MESH_MIN_Y)), in_height);
//, min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0);
stepper.synchronize();
planner.synchronize();
SERIAL_PROTOCOLPGM("Place shim under nozzle");
LCD_MESSAGEPGM(MSG_UBL_BC_INSERT);
@ -801,7 +801,7 @@
const float z1 = measure_point_with_encoder();
do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE);
stepper.synchronize();
planner.synchronize();
SERIAL_PROTOCOLPGM("Remove shim");
LCD_MESSAGEPGM(MSG_UBL_BC_REMOVE);

View File

@ -443,8 +443,8 @@
#if IS_SCARA // scale the feed rate from mm/s to degrees/s
scara_feed_factor = cartesian_xy_mm * inv_segments * feedrate;
scara_oldA = stepper.get_axis_position_degrees(A_AXIS);
scara_oldB = stepper.get_axis_position_degrees(B_AXIS);
scara_oldA = planner.get_axis_position_degrees(A_AXIS);
scara_oldB = planner.get_axis_position_degrees(B_AXIS);
#endif
const float diff[XYZE] = {

View File

@ -559,7 +559,7 @@ uint16_t max_display_update_time = 0;
no_reentry = true;
const screenFunc_t old_screen = currentScreen;
lcd_goto_screen(_lcd_synchronize);
stepper.synchronize(); // idle() is called until moves complete
planner.synchronize(); // idle() is called until moves complete
no_reentry = false;
lcd_goto_screen(old_screen);
}