|
@@ -1323,7 +1323,7 @@ inline bool code_value_bool() { return code_value_byte() > 0; }
|
1323
|
1323
|
float code_value_temp_diff() { return code_value_float(); }
|
1324
|
1324
|
#endif
|
1325
|
1325
|
|
1326
|
|
-inline millis_t code_value_millis() { return code_value_ulong(); }
|
|
1326
|
+FORCE_INLINE millis_t code_value_millis() { return code_value_ulong(); }
|
1327
|
1327
|
inline millis_t code_value_millis_from_seconds() { return code_value_float() * 1000; }
|
1328
|
1328
|
|
1329
|
1329
|
bool code_seen(char code) {
|
|
@@ -1338,16 +1338,15 @@ bool code_seen(char code) {
|
1338
|
1338
|
*/
|
1339
|
1339
|
bool get_target_extruder_from_command(int code) {
|
1340
|
1340
|
if (code_seen('T')) {
|
1341
|
|
- uint8_t t = code_value_byte();
|
1342
|
|
- if (t >= EXTRUDERS) {
|
|
1341
|
+ if (code_value_byte() >= EXTRUDERS) {
|
1343
|
1342
|
SERIAL_ECHO_START;
|
1344
|
1343
|
SERIAL_CHAR('M');
|
1345
|
1344
|
SERIAL_ECHO(code);
|
1346
|
|
- SERIAL_ECHOPAIR(" " MSG_INVALID_EXTRUDER " ", t);
|
|
1345
|
+ SERIAL_ECHOPAIR(" " MSG_INVALID_EXTRUDER " ", code_value_byte());
|
1347
|
1346
|
SERIAL_EOL;
|
1348
|
1347
|
return true;
|
1349
|
1348
|
}
|
1350
|
|
- target_extruder = t;
|
|
1349
|
+ target_extruder = code_value_byte();
|
1351
|
1350
|
}
|
1352
|
1351
|
else
|
1353
|
1352
|
target_extruder = active_extruder;
|
|
@@ -2545,10 +2544,8 @@ void gcode_get_destination() {
|
2545
|
2544
|
else
|
2546
|
2545
|
destination[i] = current_position[i];
|
2547
|
2546
|
}
|
2548
|
|
- if (code_seen('F')) {
|
2549
|
|
- float next_feedrate = code_value_linear_units();
|
2550
|
|
- if (next_feedrate > 0.0) feedrate = next_feedrate;
|
2551
|
|
- }
|
|
2547
|
+ if (code_seen('F') && code_value_linear_units() > 0.0)
|
|
2548
|
+ feedrate = code_value_linear_units();
|
2552
|
2549
|
}
|
2553
|
2550
|
|
2554
|
2551
|
void unknown_command_error() {
|
|
@@ -3160,7 +3157,6 @@ inline void gcode_G28() {
|
3160
|
3157
|
}
|
3161
|
3158
|
|
3162
|
3159
|
int8_t px, py;
|
3163
|
|
- float z;
|
3164
|
3160
|
|
3165
|
3161
|
switch (state) {
|
3166
|
3162
|
case MeshReport:
|
|
@@ -3258,24 +3254,22 @@ inline void gcode_G28() {
|
3258
|
3254
|
return;
|
3259
|
3255
|
}
|
3260
|
3256
|
if (code_seen('Z')) {
|
3261
|
|
- z = code_value_axis_units(Z_AXIS);
|
|
3257
|
+ mbl.z_values[py][px] = code_value_axis_units(Z_AXIS);
|
3262
|
3258
|
}
|
3263
|
3259
|
else {
|
3264
|
3260
|
SERIAL_PROTOCOLLNPGM("Z not entered.");
|
3265
|
3261
|
return;
|
3266
|
3262
|
}
|
3267
|
|
- mbl.z_values[py][px] = z;
|
3268
|
3263
|
break;
|
3269
|
3264
|
|
3270
|
3265
|
case MeshSetZOffset:
|
3271
|
3266
|
if (code_seen('Z')) {
|
3272
|
|
- z = code_value_axis_units(Z_AXIS);
|
|
3267
|
+ mbl.z_offset = code_value_axis_units(Z_AXIS);
|
3273
|
3268
|
}
|
3274
|
3269
|
else {
|
3275
|
3270
|
SERIAL_PROTOCOLLNPGM("Z not entered.");
|
3276
|
3271
|
return;
|
3277
|
3272
|
}
|
3278
|
|
- mbl.z_offset = z;
|
3279
|
3273
|
break;
|
3280
|
3274
|
|
3281
|
3275
|
case MeshReset:
|
|
@@ -3807,15 +3801,12 @@ inline void gcode_G92() {
|
3807
|
3801
|
#if ENABLED(ULTIPANEL)
|
3808
|
3802
|
|
3809
|
3803
|
/**
|
3810
|
|
- * M0: // M0 - Unconditional stop - Wait for user button press on LCD
|
3811
|
|
- * M1: // M1 - Conditional stop - Wait for user button press on LCD
|
|
3804
|
+ * M0: Unconditional stop - Wait for user button press on LCD
|
|
3805
|
+ * M1: Conditional stop - Wait for user button press on LCD
|
3812
|
3806
|
*/
|
3813
|
3807
|
inline void gcode_M0_M1() {
|
3814
|
3808
|
char* args = current_command_args;
|
3815
|
3809
|
|
3816
|
|
- uint8_t test_value = 12;
|
3817
|
|
- SERIAL_ECHOPAIR("TEST", test_value);
|
3818
|
|
-
|
3819
|
3810
|
millis_t codenum = 0;
|
3820
|
3811
|
bool hasP = false, hasS = false;
|
3821
|
3812
|
if (code_seen('P')) {
|
|
@@ -4037,35 +4028,34 @@ inline void gcode_M31() {
|
4037
|
4028
|
* S<byte> Pin status from 0 - 255
|
4038
|
4029
|
*/
|
4039
|
4030
|
inline void gcode_M42() {
|
4040
|
|
- if (code_seen('S')) {
|
4041
|
|
- int pin_status = code_value_int();
|
4042
|
|
- if (pin_status < 0 || pin_status > 255) return;
|
|
4031
|
+ if (!code_seen('S')) return;
|
4043
|
4032
|
|
4044
|
|
- int pin_number = code_seen('P') ? code_value_int() : LED_PIN;
|
4045
|
|
- if (pin_number < 0) return;
|
|
4033
|
+ int pin_status = code_value_int();
|
|
4034
|
+ if (pin_status < 0 || pin_status > 255) return;
|
4046
|
4035
|
|
4047
|
|
- for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
|
4048
|
|
- if (pin_number == sensitive_pins[i]) return;
|
|
4036
|
+ int pin_number = code_seen('P') ? code_value_int() : LED_PIN;
|
|
4037
|
+ if (pin_number < 0) return;
|
4049
|
4038
|
|
4050
|
|
- pinMode(pin_number, OUTPUT);
|
4051
|
|
- digitalWrite(pin_number, pin_status);
|
4052
|
|
- analogWrite(pin_number, pin_status);
|
|
4039
|
+ for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
|
|
4040
|
+ if (pin_number == sensitive_pins[i]) return;
|
4053
|
4041
|
|
4054
|
|
- #if FAN_COUNT > 0
|
4055
|
|
- switch (pin_number) {
|
4056
|
|
- #if HAS_FAN0
|
4057
|
|
- case FAN_PIN: fanSpeeds[0] = pin_status; break;
|
4058
|
|
- #endif
|
4059
|
|
- #if HAS_FAN1
|
4060
|
|
- case FAN1_PIN: fanSpeeds[1] = pin_status; break;
|
4061
|
|
- #endif
|
4062
|
|
- #if HAS_FAN2
|
4063
|
|
- case FAN2_PIN: fanSpeeds[2] = pin_status; break;
|
4064
|
|
- #endif
|
4065
|
|
- }
|
4066
|
|
- #endif
|
|
4042
|
+ pinMode(pin_number, OUTPUT);
|
|
4043
|
+ digitalWrite(pin_number, pin_status);
|
|
4044
|
+ analogWrite(pin_number, pin_status);
|
4067
|
4045
|
|
4068
|
|
- } // code_seen('S')
|
|
4046
|
+ #if FAN_COUNT > 0
|
|
4047
|
+ switch (pin_number) {
|
|
4048
|
+ #if HAS_FAN0
|
|
4049
|
+ case FAN_PIN: fanSpeeds[0] = pin_status; break;
|
|
4050
|
+ #endif
|
|
4051
|
+ #if HAS_FAN1
|
|
4052
|
+ case FAN1_PIN: fanSpeeds[1] = pin_status; break;
|
|
4053
|
+ #endif
|
|
4054
|
+ #if HAS_FAN2
|
|
4055
|
+ case FAN2_PIN: fanSpeeds[2] = pin_status; break;
|
|
4056
|
+ #endif
|
|
4057
|
+ }
|
|
4058
|
+ #endif
|
4069
|
4059
|
}
|
4070
|
4060
|
|
4071
|
4061
|
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
|
|
@@ -4335,32 +4325,27 @@ inline void gcode_M104() {
|
4335
|
4325
|
#endif
|
4336
|
4326
|
|
4337
|
4327
|
if (code_seen('S')) {
|
4338
|
|
- float temp = code_value_temp_abs();
|
4339
|
|
- thermalManager.setTargetHotend(temp, target_extruder);
|
|
4328
|
+ thermalManager.setTargetHotend(code_value_temp_abs(), target_extruder);
|
4340
|
4329
|
#if ENABLED(DUAL_X_CARRIAGE)
|
4341
|
4330
|
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0)
|
4342
|
|
- thermalManager.setTargetHotend(temp == 0.0 ? 0.0 : temp + duplicate_extruder_temp_offset, 1);
|
|
4331
|
+ thermalManager.setTargetHotend(code_value_temp_abs() == 0.0 ? 0.0 : code_value_temp_abs() + duplicate_extruder_temp_offset, 1);
|
4343
|
4332
|
#endif
|
4344
|
4333
|
|
4345
|
4334
|
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
|
4346
|
4335
|
/**
|
|
4336
|
+ * Stop the timer at the end of print, starting is managed by
|
|
4337
|
+ * 'heat and wait' M109.
|
4347
|
4338
|
* We use half EXTRUDE_MINTEMP here to allow nozzles to be put into hot
|
4348
|
4339
|
* stand by mode, for instance in a dual extruder setup, without affecting
|
4349
|
4340
|
* the running print timer.
|
4350
|
4341
|
*/
|
4351
|
|
- if (temp <= (EXTRUDE_MINTEMP)/2) {
|
|
4342
|
+ if (code_value_temp_abs() <= (EXTRUDE_MINTEMP)/2) {
|
4352
|
4343
|
print_job_timer.stop();
|
4353
|
4344
|
LCD_MESSAGEPGM(WELCOME_MSG);
|
4354
|
4345
|
}
|
4355
|
|
- /**
|
4356
|
|
- * We do not check if the timer is already running because this check will
|
4357
|
|
- * be done for us inside the Stopwatch::start() method thus a running timer
|
4358
|
|
- * will not restart.
|
4359
|
|
- */
|
4360
|
|
- else print_job_timer.start();
|
4361
|
4346
|
#endif
|
4362
|
4347
|
|
4363
|
|
- if (temp > thermalManager.degHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING);
|
|
4348
|
+ if (code_value_temp_abs() > thermalManager.degHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING);
|
4364
|
4349
|
}
|
4365
|
4350
|
}
|
4366
|
4351
|
|
|
@@ -4518,11 +4503,10 @@ inline void gcode_M109() {
|
4518
|
4503
|
|
4519
|
4504
|
bool no_wait_for_cooling = code_seen('S');
|
4520
|
4505
|
if (no_wait_for_cooling || code_seen('R')) {
|
4521
|
|
- float temp = code_value_temp_abs();
|
4522
|
|
- thermalManager.setTargetHotend(temp, target_extruder);
|
|
4506
|
+ thermalManager.setTargetHotend(code_value_temp_abs(), target_extruder);
|
4523
|
4507
|
#if ENABLED(DUAL_X_CARRIAGE)
|
4524
|
4508
|
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0)
|
4525
|
|
- thermalManager.setTargetHotend(temp == 0.0 ? 0.0 : temp + duplicate_extruder_temp_offset, 1);
|
|
4509
|
+ thermalManager.setTargetHotend(code_value_temp_abs() == 0.0 ? 0.0 : code_value_temp_abs() + duplicate_extruder_temp_offset, 1);
|
4526
|
4510
|
#endif
|
4527
|
4511
|
|
4528
|
4512
|
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
|
|
@@ -4531,7 +4515,7 @@ inline void gcode_M109() {
|
4531
|
4515
|
* stand by mode, for instance in a dual extruder setup, without affecting
|
4532
|
4516
|
* the running print timer.
|
4533
|
4517
|
*/
|
4534
|
|
- if (temp <= (EXTRUDE_MINTEMP)/2) {
|
|
4518
|
+ if (code_value_temp_abs() <= (EXTRUDE_MINTEMP)/2) {
|
4535
|
4519
|
print_job_timer.stop();
|
4536
|
4520
|
LCD_MESSAGEPGM(WELCOME_MSG);
|
4537
|
4521
|
}
|
|
@@ -4642,7 +4626,22 @@ inline void gcode_M109() {
|
4642
|
4626
|
|
4643
|
4627
|
LCD_MESSAGEPGM(MSG_BED_HEATING);
|
4644
|
4628
|
bool no_wait_for_cooling = code_seen('S');
|
4645
|
|
- if (no_wait_for_cooling || code_seen('R')) thermalManager.setTargetBed(code_value_temp_abs());
|
|
4629
|
+ if (no_wait_for_cooling || code_seen('R')) {
|
|
4630
|
+ thermalManager.setTargetBed(code_value_temp_abs());
|
|
4631
|
+ #if ENABLED(PRINTJOB_TIMER_AUTOSTART)
|
|
4632
|
+ if (code_value_temp_abs() > BED_MINTEMP) {
|
|
4633
|
+ /**
|
|
4634
|
+ * We start the timer when 'heating and waiting' command arrives, LCD
|
|
4635
|
+ * functions never wait. Cooling down managed by extruders.
|
|
4636
|
+ *
|
|
4637
|
+ * We do not check if the timer is already running because this check will
|
|
4638
|
+ * be done for us inside the Stopwatch::start() method thus a running timer
|
|
4639
|
+ * will not restart.
|
|
4640
|
+ */
|
|
4641
|
+ print_job_timer.start();
|
|
4642
|
+ }
|
|
4643
|
+ #endif
|
|
4644
|
+ }
|
4646
|
4645
|
|
4647
|
4646
|
#if TEMP_BED_RESIDENCY_TIME > 0
|
4648
|
4647
|
millis_t residency_start_ms = 0;
|
|
@@ -5178,13 +5177,12 @@ inline void gcode_M200() {
|
5178
|
5177
|
if (get_target_extruder_from_command(200)) return;
|
5179
|
5178
|
|
5180
|
5179
|
if (code_seen('D')) {
|
5181
|
|
- float diameter = code_value_linear_units();
|
5182
|
5180
|
// setting any extruder filament size disables volumetric on the assumption that
|
5183
|
5181
|
// slicers either generate in extruder values as cubic mm or as as filament feeds
|
5184
|
5182
|
// for all extruders
|
5185
|
|
- volumetric_enabled = (diameter != 0.0);
|
|
5183
|
+ volumetric_enabled = (code_value_linear_units() != 0.0);
|
5186
|
5184
|
if (volumetric_enabled) {
|
5187
|
|
- filament_size[target_extruder] = diameter;
|
|
5185
|
+ filament_size[target_extruder] = code_value_linear_units();
|
5188
|
5186
|
// make sure all extruders have some sane value for the filament size
|
5189
|
5187
|
for (int i = 0; i < EXTRUDERS; i++)
|
5190
|
5188
|
if (! filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA;
|
|
@@ -5464,11 +5462,9 @@ inline void gcode_M220() {
|
5464
|
5462
|
* M221: Set extrusion percentage (M221 T0 S95)
|
5465
|
5463
|
*/
|
5466
|
5464
|
inline void gcode_M221() {
|
5467
|
|
- if (code_seen('S')) {
|
5468
|
|
- int sval = code_value_int();
|
5469
|
|
- if (get_target_extruder_from_command(221)) return;
|
5470
|
|
- extruder_multiplier[target_extruder] = sval;
|
5471
|
|
- }
|
|
5465
|
+ if (get_target_extruder_from_command(221)) return;
|
|
5466
|
+ if (code_seen('S'))
|
|
5467
|
+ extruder_multiplier[target_extruder] = code_value_int();
|
5472
|
5468
|
}
|
5473
|
5469
|
|
5474
|
5470
|
/**
|
|
@@ -5520,28 +5516,27 @@ inline void gcode_M226() {
|
5520
|
5516
|
#if HAS_SERVOS
|
5521
|
5517
|
|
5522
|
5518
|
/**
|
5523
|
|
- * M280: Get or set servo position. P<index> S<angle>
|
|
5519
|
+ * M280: Get or set servo position. P<index> [S<angle>]
|
5524
|
5520
|
*/
|
5525
|
5521
|
inline void gcode_M280() {
|
5526
|
|
- int servo_index = code_seen('P') ? code_value_int() : -1;
|
5527
|
|
- int servo_position = 0;
|
5528
|
|
- if (code_seen('S')) {
|
5529
|
|
- servo_position = code_value_int();
|
5530
|
|
- if (servo_index >= 0 && servo_index < NUM_SERVOS)
|
5531
|
|
- MOVE_SERVO(servo_index, servo_position);
|
|
5522
|
+ if (!code_seen('P')) return;
|
|
5523
|
+ int servo_index = code_value_int();
|
|
5524
|
+ if (servo_index >= 0 && servo_index < NUM_SERVOS) {
|
|
5525
|
+ if (code_seen('S'))
|
|
5526
|
+ MOVE_SERVO(servo_index, code_value_int());
|
5532
|
5527
|
else {
|
5533
|
|
- SERIAL_ERROR_START;
|
5534
|
|
- SERIAL_ERROR("Servo ");
|
5535
|
|
- SERIAL_ERROR(servo_index);
|
5536
|
|
- SERIAL_ERRORLN(" out of range");
|
|
5528
|
+ SERIAL_ECHO_START;
|
|
5529
|
+ SERIAL_ECHOPGM(" Servo ");
|
|
5530
|
+ SERIAL_ECHO(servo_index);
|
|
5531
|
+ SERIAL_ECHOPGM(": ");
|
|
5532
|
+ SERIAL_ECHOLN(servo[servo_index].read());
|
5537
|
5533
|
}
|
5538
|
5534
|
}
|
5539
|
|
- else if (servo_index >= 0) {
|
5540
|
|
- SERIAL_ECHO_START;
|
5541
|
|
- SERIAL_ECHOPGM(" Servo ");
|
5542
|
|
- SERIAL_ECHO(servo_index);
|
5543
|
|
- SERIAL_ECHOPGM(": ");
|
5544
|
|
- SERIAL_ECHOLN(servo[servo_index].read());
|
|
5535
|
+ else {
|
|
5536
|
+ SERIAL_ERROR_START;
|
|
5537
|
+ SERIAL_ERROR("Servo ");
|
|
5538
|
+ SERIAL_ERROR(servo_index);
|
|
5539
|
+ SERIAL_ERRORLN(" out of range");
|
5545
|
5540
|
}
|
5546
|
5541
|
}
|
5547
|
5542
|
|
|
@@ -5794,11 +5789,9 @@ inline void gcode_M303() {
|
5794
|
5789
|
* M365: SCARA calibration: Scaling factor, X, Y, Z axis
|
5795
|
5790
|
*/
|
5796
|
5791
|
inline void gcode_M365() {
|
5797
|
|
- for (int8_t i = X_AXIS; i <= Z_AXIS; i++) {
|
5798
|
|
- if (code_seen(axis_codes[i])) {
|
|
5792
|
+ for (int8_t i = X_AXIS; i <= Z_AXIS; i++)
|
|
5793
|
+ if (code_seen(axis_codes[i]))
|
5799
|
5794
|
axis_scaling[i] = code_value_float();
|
5800
|
|
- }
|
5801
|
|
- }
|
5802
|
5795
|
}
|
5803
|
5796
|
|
5804
|
5797
|
#endif // SCARA
|
|
@@ -8053,7 +8046,7 @@ void idle(
|
8053
|
8046
|
void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
|
8054
|
8047
|
|
8055
|
8048
|
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
|
8056
|
|
- if (IS_SD_PRINTING && !(READ(FIL_RUNOUT_PIN) ^ FIL_RUNOUT_INVERTING))
|
|
8049
|
+ if ((IS_SD_PRINTING || print_job_timer.isRunning()) && !(READ(FIL_RUNOUT_PIN) ^ FIL_RUNOUT_INVERTING))
|
8057
|
8050
|
handle_filament_runout();
|
8058
|
8051
|
#endif
|
8059
|
8052
|
|