Cleaning up code in prep for merge with upstream.
This commit is contained in:
parent
745d9fe1a4
commit
a57862e29f
|
@ -330,7 +330,6 @@ const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
|
||||
//#define DISABLE_MAX_ENDSTOPS
|
||||
//#define DISABLE_MIN_ENDSTOPS
|
||||
// If you want to enable the Z Probe pin, but disable its use, uncomment the line below.
|
||||
|
|
|
@ -231,7 +231,6 @@ void refresh_cmd_timeout(void);
|
|||
extern float homing_feedrate[];
|
||||
extern bool axis_relative_modes[];
|
||||
extern int feedmultiply;
|
||||
extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
|
||||
extern bool volumetric_enabled;
|
||||
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
|
||||
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.
|
||||
|
|
|
@ -170,10 +170,10 @@
|
|||
// M404 - N<dia in mm> Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters
|
||||
// M405 - Turn on Filament Sensor extrusion control. Optional D<delay in cm> to set delay in centimeters between sensor and extruder
|
||||
// M406 - Turn off Filament Sensor extrusion control
|
||||
// M407 - Displays measured filament diameter
|
||||
// M407 - Display measured filament diameter
|
||||
// M500 - Store parameters in EEPROM
|
||||
// M501 - Read parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||
// M502 - Revert to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
// M502 - Revert to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||
// M503 - Print the current settings (from memory not from EEPROM). Use S0 to leave off headings.
|
||||
// M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
|
||||
// M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
|
||||
|
@ -272,7 +272,7 @@ int fanSpeed = 0;
|
|||
|
||||
#endif // FWRETRACT
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
#if defined(ULTIPANEL) && HAS_POWER_SWITCH
|
||||
bool powersupply =
|
||||
#ifdef PS_DEFAULT_OFF
|
||||
false
|
||||
|
@ -311,13 +311,13 @@ bool cancel_heatup = false;
|
|||
|
||||
#ifdef FILAMENT_SENSOR
|
||||
//Variables for Filament Sensor input
|
||||
float filament_width_nominal=DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
|
||||
bool filament_sensor=false; //M405 turns on filament_sensor control, M406 turns it off
|
||||
float filament_width_meas=DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
|
||||
float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
|
||||
bool filament_sensor = false; //M405 turns on filament_sensor control, M406 turns it off
|
||||
float filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
|
||||
signed char measurement_delay[MAX_MEASUREMENT_DELAY+1]; //ring buffer to delay measurement store extruder factor after subtracting 100
|
||||
int delay_index1=0; //index into ring buffer
|
||||
int delay_index2=-1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
|
||||
float delay_dist=0; //delay distance counter
|
||||
int delay_index1 = 0; //index into ring buffer
|
||||
int delay_index2 = -1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
|
||||
float delay_dist = 0; //delay distance counter
|
||||
int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
|
||||
#endif
|
||||
|
||||
|
@ -516,8 +516,8 @@ void setup_powerhold()
|
|||
#if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
|
||||
OUT_WRITE(SUICIDE_PIN, HIGH);
|
||||
#endif
|
||||
#if defined(PS_ON_PIN) && PS_ON_PIN > -1
|
||||
#if defined(PS_DEFAULT_OFF)
|
||||
#if HAS_POWER_SWITCH
|
||||
#ifdef PS_DEFAULT_OFF
|
||||
OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
|
||||
#else
|
||||
OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE);
|
||||
|
@ -1100,7 +1100,7 @@ inline void sync_plan_position() {
|
|||
static void run_z_probe() {
|
||||
|
||||
#ifdef DELTA
|
||||
|
||||
|
||||
float start_z = current_position[Z_AXIS];
|
||||
long start_steps = st_get_position(Z_AXIS);
|
||||
|
||||
|
@ -1153,7 +1153,7 @@ inline void sync_plan_position() {
|
|||
current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
|
||||
// make sure the planner knows where we are as it may be a bit different than we last said to move to
|
||||
sync_plan_position();
|
||||
|
||||
|
||||
#endif // !DELTA
|
||||
}
|
||||
|
||||
|
@ -1163,7 +1163,7 @@ inline void sync_plan_position() {
|
|||
#ifdef DELTA
|
||||
|
||||
feedrate = XY_TRAVEL_SPEED;
|
||||
|
||||
|
||||
destination[X_AXIS] = x;
|
||||
destination[Y_AXIS] = y;
|
||||
destination[Z_AXIS] = z;
|
||||
|
@ -1237,12 +1237,12 @@ inline void sync_plan_position() {
|
|||
feedrate = homing_feedrate[X_AXIS]/10;
|
||||
destination[X_AXIS] = 0;
|
||||
prepare_move_raw();
|
||||
|
||||
|
||||
// Home Y for safety
|
||||
feedrate = homing_feedrate[X_AXIS]/2;
|
||||
destination[Y_AXIS] = 0;
|
||||
prepare_move_raw();
|
||||
|
||||
|
||||
st_synchronize();
|
||||
|
||||
#if defined(Z_PROBE_ENDSTOP)
|
||||
|
@ -1250,7 +1250,7 @@ inline void sync_plan_position() {
|
|||
if (z_probe_endstop) {
|
||||
#else
|
||||
bool z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
if (!z_min_endstop) {
|
||||
if (z_min_endstop) {
|
||||
#endif
|
||||
if (!Stopped) {
|
||||
SERIAL_ERROR_START;
|
||||
|
@ -1261,7 +1261,7 @@ inline void sync_plan_position() {
|
|||
}
|
||||
|
||||
#endif // Z_PROBE_ALLEN_KEY
|
||||
|
||||
|
||||
}
|
||||
|
||||
static void retract_z_probe() {
|
||||
|
@ -1279,9 +1279,9 @@ inline void sync_plan_position() {
|
|||
#if SERVO_LEVELING
|
||||
servos[servo_endstops[Z_AXIS]].attach(0);
|
||||
#endif
|
||||
|
||||
servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2 + 1]);
|
||||
|
||||
|
||||
servos[servo_endstops[Z_AXIS]].write(servo_endstop_angles[Z_AXIS * 2 + 1]);
|
||||
|
||||
#if SERVO_LEVELING
|
||||
delay(PROBE_SERVO_DEACTIVATION_DELAY);
|
||||
servos[servo_endstops[Z_AXIS]].detach();
|
||||
|
@ -1305,23 +1305,23 @@ inline void sync_plan_position() {
|
|||
feedrate = homing_feedrate[Z_AXIS]/10;
|
||||
destination[Z_AXIS] = current_position[Z_AXIS] - Z_PROBE_ALLEN_KEY_RETRACT_DEPTH;
|
||||
prepare_move_raw();
|
||||
|
||||
|
||||
// Move up for safety
|
||||
feedrate = homing_feedrate[Z_AXIS]/2;
|
||||
destination[Z_AXIS] = current_position[Z_AXIS] + Z_PROBE_ALLEN_KEY_RETRACT_DEPTH * 2;
|
||||
prepare_move_raw();
|
||||
|
||||
|
||||
// Home XY for safety
|
||||
feedrate = homing_feedrate[X_AXIS]/2;
|
||||
destination[X_AXIS] = 0;
|
||||
destination[Y_AXIS] = 0;
|
||||
prepare_move_raw();
|
||||
|
||||
|
||||
st_synchronize();
|
||||
|
||||
#if defined(Z_PROBE_ENDSTOP)
|
||||
bool z_probe_endstop = (READ(Z_PROBE_PIN) != Z_PROBE_ENDSTOP_INVERTING);
|
||||
if (z_probe_endstop) {
|
||||
if (!z_probe_endstop) {
|
||||
#else
|
||||
bool z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
if (!z_min_endstop) {
|
||||
|
@ -3319,7 +3319,7 @@ inline void gcode_M140() {
|
|||
if (code_seen('S')) setTargetBed(code_value());
|
||||
}
|
||||
|
||||
#if defined(PS_ON_PIN) && PS_ON_PIN > -1
|
||||
#if HAS_POWER_SWITCH
|
||||
|
||||
/**
|
||||
* M80: Turn on Power Supply
|
||||
|
@ -3341,10 +3341,12 @@ inline void gcode_M140() {
|
|||
#endif
|
||||
}
|
||||
|
||||
#endif // PS_ON_PIN
|
||||
#endif // HAS_POWER_SWITCH
|
||||
|
||||
/**
|
||||
* M81: Turn off Power Supply
|
||||
* M81: Turn off Power, including Power Supply, if there is one.
|
||||
*
|
||||
* This code should ALWAYS be available for EMERGENCY SHUTDOWN!
|
||||
*/
|
||||
inline void gcode_M81() {
|
||||
disable_heater();
|
||||
|
@ -3359,16 +3361,19 @@ inline void gcode_M81() {
|
|||
#if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
|
||||
st_synchronize();
|
||||
suicide();
|
||||
#elif defined(PS_ON_PIN) && PS_ON_PIN > -1
|
||||
#elif HAS_POWER_SWITCH
|
||||
OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
|
||||
#endif
|
||||
#ifdef ULTIPANEL
|
||||
powersupply = false;
|
||||
#if HAS_POWER_SWITCH
|
||||
powersupply = false;
|
||||
#endif
|
||||
LCD_MESSAGEPGM(MACHINE_NAME " " MSG_OFF ".");
|
||||
lcd_update();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* M82: Set E codes absolute (default)
|
||||
*/
|
||||
|
@ -4903,15 +4908,15 @@ void process_commands() {
|
|||
#endif //HEATER_2_PIN
|
||||
#endif //BARICUDA
|
||||
|
||||
#if defined(PS_ON_PIN) && PS_ON_PIN > -1
|
||||
#if HAS_POWER_SWITCH
|
||||
|
||||
case 80: // M80 - Turn on Power Supply
|
||||
gcode_M80();
|
||||
break;
|
||||
|
||||
#endif // PS_ON_PIN
|
||||
#endif // HAS_POWER_SWITCH
|
||||
|
||||
case 81: // M81 - Turn off Power Supply
|
||||
case 81: // M81 - Turn off Power, including Power Supply, if possible
|
||||
gcode_M81();
|
||||
break;
|
||||
|
||||
|
@ -5882,19 +5887,17 @@ void kill()
|
|||
disable_e2();
|
||||
disable_e3();
|
||||
|
||||
#if defined(PS_ON_PIN) && PS_ON_PIN > -1
|
||||
pinMode(PS_ON_PIN,INPUT);
|
||||
#endif
|
||||
#if HAS_POWER_SWITCH
|
||||
pinMode(PS_ON_PIN, INPUT);
|
||||
#endif
|
||||
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
|
||||
LCD_ALERTMESSAGEPGM(MSG_KILLED);
|
||||
|
||||
// FMC small patch to update the LCD before ending
|
||||
sei(); // enable interrupts
|
||||
for ( int i=5; i--; lcd_update())
|
||||
{
|
||||
delay(200);
|
||||
}
|
||||
for (int i = 5; i--; lcd_update()) delay(200); // Wait a short time
|
||||
cli(); // disable interrupts
|
||||
suicide();
|
||||
while(1) { /* Intentionally left empty */ } // Wait for reset
|
||||
|
|
|
@ -369,7 +369,7 @@ static void lcd_implementation_status_screen() {
|
|||
lcd_printPGM(PSTR("dia:"));
|
||||
lcd_print(ftostr12ns(filament_width_meas));
|
||||
lcd_printPGM(PSTR(" factor:"));
|
||||
lcd_print(itostr3(extrudemultiply));
|
||||
lcd_print(itostr3(volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]));
|
||||
lcd_print('%');
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -545,7 +545,7 @@ float junction_deviation = 0.1;
|
|||
block->steps[Z_AXIS] = labs(dz);
|
||||
block->steps[E_AXIS] = labs(de);
|
||||
block->steps[E_AXIS] *= volumetric_multiplier[active_extruder];
|
||||
block->steps[E_AXIS] *= extrudemultiply;
|
||||
block->steps[E_AXIS] *= extruder_multiply[active_extruder];
|
||||
block->steps[E_AXIS] /= 100;
|
||||
block->step_event_count = max(block->steps[X_AXIS], max(block->steps[Y_AXIS], max(block->steps[Z_AXIS], block->steps[E_AXIS])));
|
||||
|
||||
|
@ -679,7 +679,7 @@ float junction_deviation = 0.1;
|
|||
delta_mm[Y_AXIS] = dy / axis_steps_per_unit[Y_AXIS];
|
||||
#endif
|
||||
delta_mm[Z_AXIS] = dz / axis_steps_per_unit[Z_AXIS];
|
||||
delta_mm[E_AXIS] = (de / axis_steps_per_unit[E_AXIS]) * volumetric_multiplier[active_extruder] * extrudemultiply / 100.0;
|
||||
delta_mm[E_AXIS] = (de / axis_steps_per_unit[E_AXIS]) * volumetric_multiplier[active_extruder] * extruder_multiply[active_extruder] / 100.0;
|
||||
|
||||
if (block->steps[X_AXIS] <= dropsegments && block->steps[Y_AXIS] <= dropsegments && block->steps[Z_AXIS] <= dropsegments) {
|
||||
block->millimeters = fabs(delta_mm[E_AXIS]);
|
||||
|
|
|
@ -524,33 +524,43 @@ ISR(TIMER1_COMPA_vect) {
|
|||
}
|
||||
|
||||
if (TEST(out_bits, Z_AXIS)) { // -direction
|
||||
|
||||
Z_APPLY_DIR(INVERT_Z_DIR,0);
|
||||
count_direction[Z_AXIS] = -1;
|
||||
if (check_endstops)
|
||||
{
|
||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
||||
#ifndef Z_DUAL_ENDSTOPS
|
||||
UPDATE_ENDSTOP(z, Z, min, MIN);
|
||||
#else
|
||||
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
#if defined(Z2_MIN_PIN) && Z2_MIN_PIN > -1
|
||||
bool z2_min_endstop=(READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING);
|
||||
#else
|
||||
bool z2_min_endstop=z_min_endstop;
|
||||
#endif
|
||||
if(((z_min_endstop && old_z_min_endstop) || (z2_min_endstop && old_z2_min_endstop)) && (current_block->steps[Z_AXIS] > 0))
|
||||
{
|
||||
|
||||
if (check_endstops) {
|
||||
|
||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0
|
||||
|
||||
#ifdef Z_DUAL_ENDSTOPS
|
||||
|
||||
bool z_min_endstop = READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING,
|
||||
z2_min_endstop =
|
||||
#if defined(Z2_MIN_PIN) && Z2_MIN_PIN >= 0
|
||||
READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING
|
||||
#else
|
||||
z_min_endstop
|
||||
#endif
|
||||
;
|
||||
|
||||
bool z_min_both = z_min_endstop && old_z_min_endstop,
|
||||
z2_min_both = z2_min_endstop && old_z2_min_endstop;
|
||||
if ((z_min_both || z2_min_both) && current_block->steps[Z_AXIS] > 0) {
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_hit=true;
|
||||
if (!(performing_homing) || ((performing_homing)&&(z_min_endstop && old_z_min_endstop)&&(z2_min_endstop && old_z2_min_endstop))) //if not performing home or if both endstops were trigged during homing...
|
||||
{
|
||||
endstop_z_hit = true;
|
||||
if (!performing_homing || (performing_homing && z_min_both && z2_min_both)) //if not performing home or if both endstops were trigged during homing...
|
||||
step_events_completed = current_block->step_event_count;
|
||||
}
|
||||
}
|
||||
old_z_min_endstop = z_min_endstop;
|
||||
old_z2_min_endstop = z2_min_endstop;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#else // !Z_DUAL_ENDSTOPS
|
||||
|
||||
UPDATE_ENDSTOP(z, Z, min, MIN);
|
||||
|
||||
#endif // !Z_DUAL_ENDSTOPS
|
||||
|
||||
#endif // Z_MIN_PIN
|
||||
|
||||
#ifdef Z_PROBE_ENDSTOP
|
||||
UPDATE_ENDSTOP(z, Z, probe, PROBE);
|
||||
|
@ -564,41 +574,53 @@ ISR(TIMER1_COMPA_vect) {
|
|||
}
|
||||
old_z_probe_endstop = z_probe_endstop;
|
||||
#endif
|
||||
}
|
||||
|
||||
} // check_endstops
|
||||
|
||||
}
|
||||
else { // +direction
|
||||
|
||||
Z_APPLY_DIR(!INVERT_Z_DIR,0);
|
||||
count_direction[Z_AXIS] = 1;
|
||||
|
||||
if (check_endstops) {
|
||||
|
||||
#if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0
|
||||
#ifndef Z_DUAL_ENDSTOPS
|
||||
UPDATE_ENDSTOP(z, Z, max, MAX);
|
||||
#else
|
||||
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
|
||||
#if defined(Z2_MAX_PIN) && Z2_MAX_PIN > -1
|
||||
bool z2_max_endstop=(READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING);
|
||||
#else
|
||||
bool z2_max_endstop=z_max_endstop;
|
||||
#endif
|
||||
if(((z_max_endstop && old_z_max_endstop) || (z2_max_endstop && old_z2_max_endstop)) && (current_block->steps[Z_AXIS] > 0))
|
||||
{
|
||||
|
||||
#ifdef Z_DUAL_ENDSTOPS
|
||||
|
||||
bool z_max_endstop = READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING,
|
||||
z2_max_endstop =
|
||||
#if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0
|
||||
READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING
|
||||
#else
|
||||
z_max_endstop
|
||||
#endif
|
||||
;
|
||||
|
||||
bool z_max_both = z_max_endstop && old_z_max_endstop,
|
||||
z2_max_both = z2_max_endstop && old_z2_max_endstop;
|
||||
if ((z_max_both || z2_max_both) && current_block->steps[Z_AXIS] > 0) {
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_hit=true;
|
||||
endstop_z_hit = true;
|
||||
|
||||
// if (z_max_endstop && old_z_max_endstop) SERIAL_ECHOLN("z_max_endstop = true");
|
||||
// if (z2_max_endstop && old_z2_max_endstop) SERIAL_ECHOLN("z2_max_endstop = true");
|
||||
// if (z_max_both) SERIAL_ECHOLN("z_max_endstop = true");
|
||||
// if (z2_max_both) SERIAL_ECHOLN("z2_max_endstop = true");
|
||||
|
||||
|
||||
if (!(performing_homing) || ((performing_homing)&&(z_max_endstop && old_z_max_endstop)&&(z2_max_endstop && old_z2_max_endstop))) //if not performing home or if both endstops were trigged during homing...
|
||||
{
|
||||
if (!performing_homing || (performing_homing && z_max_both && z2_max_both)) //if not performing home or if both endstops were trigged during homing...
|
||||
step_events_completed = current_block->step_event_count;
|
||||
}
|
||||
}
|
||||
old_z_max_endstop = z_max_endstop;
|
||||
old_z2_max_endstop = z2_max_endstop;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#else // !Z_DUAL_ENDSTOPS
|
||||
|
||||
UPDATE_ENDSTOP(z, Z, max, MAX);
|
||||
|
||||
#endif // !Z_DUAL_ENDSTOPS
|
||||
|
||||
#endif // Z_MAX_PIN
|
||||
|
||||
#ifdef Z_PROBE_ENDSTOP
|
||||
UPDATE_ENDSTOP(z, Z, probe, PROBE);
|
||||
z_probe_endstop=(READ(Z_PROBE_PIN) != Z_PROBE_ENDSTOP_INVERTING);
|
||||
|
@ -610,22 +632,24 @@ ISR(TIMER1_COMPA_vect) {
|
|||
}
|
||||
old_z_probe_endstop = z_probe_endstop;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
} // check_endstops
|
||||
|
||||
} // +direction
|
||||
|
||||
#ifndef ADVANCE
|
||||
if (TEST(out_bits, E_AXIS)) { // -direction
|
||||
REV_E_DIR();
|
||||
count_direction[E_AXIS]=-1;
|
||||
count_direction[E_AXIS] = -1;
|
||||
}
|
||||
else { // +direction
|
||||
NORM_E_DIR();
|
||||
count_direction[E_AXIS]=1;
|
||||
count_direction[E_AXIS] = 1;
|
||||
}
|
||||
#endif //!ADVANCE
|
||||
|
||||
// Take multiple steps per interrupt (For high speed moves)
|
||||
for (int8_t i=0; i < step_loops; i++) {
|
||||
for (int8_t i = 0; i < step_loops; i++) {
|
||||
#ifndef AT90USB
|
||||
MSerial.checkRx(); // Check for serial chars.
|
||||
#endif
|
||||
|
|
|
@ -491,7 +491,7 @@ static void lcd_tune_menu() {
|
|||
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
|
||||
#endif
|
||||
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
|
||||
MENU_ITEM_EDIT(int3, MSG_FLOW, &extrudemultiply, 10, 999);
|
||||
MENU_ITEM_EDIT(int3, MSG_FLOW, &extruder_multiply[active_extruder], 10, 999);
|
||||
MENU_ITEM_EDIT(int3, MSG_FLOW MSG_F0, &extruder_multiply[0], 10, 999);
|
||||
#if TEMP_SENSOR_1 != 0
|
||||
MENU_ITEM_EDIT(int3, MSG_FLOW MSG_F1, &extruder_multiply[1], 10, 999);
|
||||
|
|
|
@ -624,7 +624,7 @@ static void lcd_implementation_status_screen()
|
|||
|
||||
static void lcd_implementation_drawmenu_generic(bool sel, uint8_t row, const char* pstr, char pre_char, char post_char) {
|
||||
char c;
|
||||
uint8_t n = LCD_WIDTH - 1 - (LCD_WIDTH < 20 ? 1 : 2);
|
||||
uint8_t n = LCD_WIDTH - 2;
|
||||
lcd.setCursor(0, row);
|
||||
lcd.print(sel ? pre_char : ' ');
|
||||
while ((c = pgm_read_byte(pstr)) && n > 0) {
|
||||
|
@ -633,12 +633,11 @@ static void lcd_implementation_drawmenu_generic(bool sel, uint8_t row, const cha
|
|||
}
|
||||
while(n--) lcd.print(' ');
|
||||
lcd.print(post_char);
|
||||
lcd.print(' ');
|
||||
}
|
||||
|
||||
static void lcd_implementation_drawmenu_setting_edit_generic(bool sel, uint8_t row, const char* pstr, char pre_char, char* data) {
|
||||
char c;
|
||||
uint8_t n = LCD_WIDTH - 1 - (LCD_WIDTH < 20 ? 1 : 2) - lcd_strlen(data);
|
||||
uint8_t n = LCD_WIDTH - 2 - lcd_strlen(data);
|
||||
lcd.setCursor(0, row);
|
||||
lcd.print(sel ? pre_char : ' ');
|
||||
while ((c = pgm_read_byte(pstr)) && n > 0) {
|
||||
|
@ -651,7 +650,7 @@ static void lcd_implementation_drawmenu_setting_edit_generic(bool sel, uint8_t r
|
|||
}
|
||||
static void lcd_implementation_drawmenu_setting_edit_generic_P(bool sel, uint8_t row, const char* pstr, char pre_char, const char* data) {
|
||||
char c;
|
||||
uint8_t n = LCD_WIDTH - 1 - (LCD_WIDTH < 20 ? 1 : 2) - lcd_strlen_P(data);
|
||||
uint8_t n = LCD_WIDTH - 2 - lcd_strlen_P(data);
|
||||
lcd.setCursor(0, row);
|
||||
lcd.print(sel ? pre_char : ' ');
|
||||
while ((c = pgm_read_byte(pstr)) && n > 0) {
|
||||
|
@ -688,11 +687,11 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
|
|||
lcd.setCursor(1, 1);
|
||||
lcd_printPGM(pstr);
|
||||
lcd.print(':');
|
||||
lcd.setCursor(LCD_WIDTH - (LCD_WIDTH < 20 ? 0 : 1) - lcd_strlen(value), 1);
|
||||
lcd.setCursor(LCD_WIDTH - lcd_strlen(value), 1);
|
||||
lcd_print(value);
|
||||
}
|
||||
|
||||
static void lcd_implementation_drawmenu_sd(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename, uint8_t concat) {
|
||||
static void lcd_implementation_drawmenu_sd(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename, uint8_t concat, char post_char) {
|
||||
char c;
|
||||
uint8_t n = LCD_WIDTH - concat;
|
||||
lcd.setCursor(0, row);
|
||||
|
@ -706,14 +705,15 @@ static void lcd_implementation_drawmenu_sd(bool sel, uint8_t row, const char* ps
|
|||
filename++;
|
||||
}
|
||||
while (n--) lcd.print(' ');
|
||||
lcd.print(post_char);
|
||||
}
|
||||
|
||||
static void lcd_implementation_drawmenu_sdfile(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename) {
|
||||
lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 1);
|
||||
lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2, ' ');
|
||||
}
|
||||
|
||||
static void lcd_implementation_drawmenu_sddirectory(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename) {
|
||||
lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2);
|
||||
lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2, LCD_STR_FOLDER[0]);
|
||||
}
|
||||
|
||||
#define lcd_implementation_drawmenu_back(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0])
|
||||
|
|
Loading…
Reference in a new issue