Browse Source

Move sync_plan_position closer to the top

pull/1/head
Scott Lahteine 8 years ago
parent
commit
db5df9500b
  1. 27
      Marlin/Marlin_main.cpp

27
Marlin/Marlin_main.cpp

@ -610,6 +610,20 @@ static void report_current_position();
print_xyz(PSTR(STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
#endif
/**
* sync_plan_position
* Set planner / stepper positions to the cartesian current_position.
* The stepper code translates these coordinates into step units.
* Allows translation between steps and millimeters for cartesian & core robots
*/
inline void sync_plan_position() {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position);
#endif
planner.set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
}
inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
#if ENABLED(DELTA) || ENABLED(SCARA)
inline void sync_plan_position_delta() {
#if ENABLED(DEBUG_LEVELING_FEATURE)
@ -1627,19 +1641,6 @@ inline void line_to_destination(float fr_mm_m) {
}
inline void line_to_destination() { line_to_destination(feedrate_mm_m); }
/**
* sync_plan_position
* Set planner / stepper positions to the cartesian current_position.
* The stepper code translates these coordinates into step units.
* Allows translation between steps and millimeters for cartesian & core robots
*/
inline void sync_plan_position() {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position);
#endif
planner.set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
}
inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); }
inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); }

Loading…
Cancel
Save