Move M428 to cpp

2.0.x
Scott Lahteine 7 years ago
parent 1fe25271e4
commit aab5489962

@ -359,10 +359,6 @@ void quickstop_stepper() {
SYNC_PLAN_POSITION_KINEMATIC(); SYNC_PLAN_POSITION_KINEMATIC();
} }
#if HAS_M206_COMMAND
#include "gcode/geometry/M428.h"
#endif
#include "gcode/eeprom/M500.h" #include "gcode/eeprom/M500.h"
#include "gcode/eeprom/M501.h" #include "gcode/eeprom/M501.h"
#include "gcode/eeprom/M502.h" #include "gcode/eeprom/M502.h"

@ -122,7 +122,6 @@ extern void gcode_M165();
extern void gcode_M350(); extern void gcode_M350();
extern void gcode_M351(); extern void gcode_M351();
extern void gcode_M355(); extern void gcode_M355();
extern void gcode_M428();
extern void gcode_M500(); extern void gcode_M500();
extern void gcode_M501(); extern void gcode_M501();
extern void gcode_M502(); extern void gcode_M502();
@ -631,9 +630,7 @@ void GcodeSuite::process_next_command() {
#endif #endif
#if HAS_M206_COMMAND #if HAS_M206_COMMAND
case 428: // M428: Apply current_position to home_offset case 428: M428(); break; // M428: Apply current_position to home_offset
gcode_M428();
break;
#endif #endif
case 500: // M500: Store settings in EEPROM case 500: // M500: Store settings in EEPROM

@ -20,6 +20,16 @@
* *
*/ */
#include "../../inc/MarlinConfig.h"
#if HAS_M206_COMMAND
#include "../gcode.h"
#include "../../module/motion.h"
#include "../../lcd/ultralcd.h"
#include "../../libs/buzzer.h"
#include "../../Marlin.h" // for axis_homed
/** /**
* M428: Set home_offset based on the distance between the * M428: Set home_offset based on the distance between the
* current_position and the nearest "reference point." * current_position and the nearest "reference point."
@ -31,7 +41,7 @@
* *
* Use M206 to set these values directly. * Use M206 to set these values directly.
*/ */
void gcode_M428() { void GcodeSuite::M428() {
bool err = false; bool err = false;
LOOP_XYZ(i) { LOOP_XYZ(i) {
if (axis_homed[i]) { if (axis_homed[i]) {
@ -59,3 +69,5 @@ void gcode_M428() {
BUZZ(100, 698); BUZZ(100, 698);
} }
} }
#endif // HAS_M206_COMMAND
Loading…
Cancel
Save