Merge pull request #4027 from gudnimg/minor-optimisation-gudni
Many minor optimisations for 3.13/3.14
This commit is contained in:
commit
2dcaae80d5
|
|
@ -498,7 +498,7 @@ bool PAT9125_sensor::updatePAT9125() {
|
|||
}
|
||||
}
|
||||
|
||||
if (!pollingTimer.running() || pollingTimer.expired(pollingPeriod)) {
|
||||
if (pollingTimer.expired_cont(pollingPeriod)) {
|
||||
pollingTimer.start();
|
||||
if (!pat9125_update()) {
|
||||
init(); // try to reinit.
|
||||
|
|
|
|||
|
|
@ -304,8 +304,6 @@ extern float retract_length_swap;
|
|||
extern float retract_recover_length_swap;
|
||||
#endif
|
||||
|
||||
extern uint8_t host_keepalive_interval;
|
||||
|
||||
extern uint32_t starttime; // milliseconds
|
||||
extern uint32_t pause_time; // milliseconds
|
||||
extern uint32_t start_pause_print; // milliseconds
|
||||
|
|
@ -319,9 +317,7 @@ extern uint32_t total_filament_used; // mm/100 or 10um
|
|||
/// @param _total_filament_used has unit mm/100 or 10um
|
||||
/// @param _total_print_time has unit minutes, for example 123 minutes
|
||||
void save_statistics(uint32_t _total_filament_used, uint32_t _total_print_time);
|
||||
extern uint8_t heating_status_counter;
|
||||
|
||||
extern bool fan_state[2];
|
||||
extern int fan_edge_counter[2];
|
||||
extern int fan_speed[2];
|
||||
|
||||
|
|
@ -352,9 +348,6 @@ extern uint16_t print_time_to_change_silent;
|
|||
|
||||
#define PRINT_TIME_REMAINING_INIT 0xffff
|
||||
|
||||
extern uint16_t mcode_in_progress;
|
||||
extern uint16_t gcode_in_progress;
|
||||
|
||||
extern LongTimer safetyTimer;
|
||||
|
||||
#define PRINT_PERCENT_DONE_INIT 0xff
|
||||
|
|
@ -424,7 +417,6 @@ void setup_fan_interrupt();
|
|||
|
||||
extern bool recover_machine_state_after_power_panic();
|
||||
extern void restore_print_from_eeprom(bool mbl_was_active);
|
||||
extern void position_menu();
|
||||
|
||||
extern void print_world_coordinates();
|
||||
extern void print_physical_coordinates();
|
||||
|
|
|
|||
|
|
@ -183,13 +183,10 @@ bool mesh_bed_leveling_flag = false;
|
|||
|
||||
uint32_t total_filament_used;
|
||||
HeatingStatus heating_status;
|
||||
uint8_t heating_status_counter;
|
||||
bool loading_flag = false;
|
||||
|
||||
#define XY_NO_RESTORE_FLAG (mesh_bed_leveling_flag || homing_flag)
|
||||
|
||||
|
||||
bool fan_state[2];
|
||||
int fan_edge_counter[2];
|
||||
int fan_speed[2];
|
||||
|
||||
|
|
@ -245,11 +242,11 @@ uint8_t newFanSpeed = 0;
|
|||
bool powersupply = true;
|
||||
#endif
|
||||
|
||||
bool cancel_heatup = false;
|
||||
static bool cancel_heatup = false;
|
||||
|
||||
int8_t busy_state = NOT_BUSY;
|
||||
static long prev_busy_signal_ms = -1;
|
||||
uint8_t host_keepalive_interval = HOST_KEEPALIVE_INTERVAL;
|
||||
static uint8_t host_keepalive_interval = HOST_KEEPALIVE_INTERVAL;
|
||||
|
||||
const char errormagic[] PROGMEM = "Error:";
|
||||
const char echomagic[] PROGMEM = "echo:";
|
||||
|
|
@ -259,9 +256,9 @@ const char echomagic[] PROGMEM = "echo:";
|
|||
#define X_COORD_INVALID (X_MIN_POS-1)
|
||||
|
||||
#define SAVED_START_POSITION_UNSET X_COORD_INVALID
|
||||
float saved_start_position[NUM_AXIS] = {SAVED_START_POSITION_UNSET, 0, 0, 0};
|
||||
static float saved_start_position[NUM_AXIS] = {SAVED_START_POSITION_UNSET, 0, 0, 0};
|
||||
|
||||
uint16_t saved_segment_idx = 0;
|
||||
static uint16_t saved_segment_idx = 0;
|
||||
|
||||
// storing estimated time to end of print counted by slicer
|
||||
uint8_t print_percent_done_normal = PRINT_PERCENT_DONE_INIT;
|
||||
|
|
@ -293,16 +290,16 @@ static float next_feedrate;
|
|||
// Original feedrate saved during homing moves
|
||||
static float saved_feedrate;
|
||||
|
||||
const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; // Sensitive pin list for M42
|
||||
static const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; // Sensitive pin list for M42
|
||||
|
||||
//static float tt = 0;
|
||||
//static float bt = 0;
|
||||
|
||||
//Inactivity shutdown variables
|
||||
static LongTimer previous_millis_cmd;
|
||||
unsigned long max_inactive_time = 0;
|
||||
static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l;
|
||||
static unsigned long safetytimer_inactive_time = DEFAULT_SAFETYTIMER_TIME_MINS*60*1000ul;
|
||||
static uint32_t max_inactive_time = 0;
|
||||
static uint32_t stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l;
|
||||
static uint32_t safetytimer_inactive_time = DEFAULT_SAFETYTIMER_TIME_MINS*60*1000ul;
|
||||
|
||||
uint32_t starttime;
|
||||
uint32_t pause_time;
|
||||
|
|
@ -316,12 +313,12 @@ bool processing_tcode; // Helper variable to block certain functions while T-cod
|
|||
Servo servos[NUM_SERVOS];
|
||||
#endif
|
||||
|
||||
bool target_direction;
|
||||
static bool target_direction;
|
||||
|
||||
//Insert variables if CHDK is defined
|
||||
#ifdef CHDK
|
||||
unsigned long chdkHigh = 0;
|
||||
bool chdkActive = false;
|
||||
static uint32_t chdkHigh = 0;
|
||||
static bool chdkActive = false;
|
||||
#endif
|
||||
|
||||
//! @name RAM save/restore printing
|
||||
|
|
@ -411,8 +408,8 @@ static void temp_compensation_apply();
|
|||
static uint8_t get_PRUSA_SN(char* SN);
|
||||
#endif //PRUSA_SN_SUPPORT
|
||||
|
||||
uint16_t gcode_in_progress = 0;
|
||||
uint16_t mcode_in_progress = 0;
|
||||
static uint16_t gcode_in_progress = 0;
|
||||
static uint16_t mcode_in_progress = 0;
|
||||
|
||||
void serial_echopair_P(const char *s_P, float v)
|
||||
{ serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
|
|
@ -623,8 +620,7 @@ void crashdet_detected(uint8_t mask)
|
|||
lcd_print(msg);
|
||||
|
||||
// ask whether to resume printing
|
||||
lcd_set_cursor(0, 1);
|
||||
lcd_puts_P(_T(MSG_RESUME_PRINT));
|
||||
lcd_puts_at_P(0, 1, _T(MSG_RESUME_PRINT));
|
||||
lcd_putc('?');
|
||||
uint8_t yesno = lcd_show_yes_no_and_wait(false);
|
||||
if (yesno == LCD_LEFT_BUTTON_CHOICE)
|
||||
|
|
@ -876,17 +872,11 @@ static void check_if_fw_is_on_right_printer() {
|
|||
uint8_t check_printer_version()
|
||||
{
|
||||
uint8_t version_changed = 0;
|
||||
uint16_t printer_type = eeprom_read_word((uint16_t*)EEPROM_PRINTER_TYPE);
|
||||
uint16_t motherboard = eeprom_read_word((uint16_t*)EEPROM_BOARD_TYPE);
|
||||
uint16_t printer_type = eeprom_init_default_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
|
||||
uint16_t motherboard = eeprom_init_default_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
|
||||
|
||||
if (printer_type != PRINTER_TYPE) {
|
||||
if (printer_type == 0xffff) eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
|
||||
else version_changed |= 0b10;
|
||||
}
|
||||
if (motherboard != MOTHERBOARD) {
|
||||
if(motherboard == 0xffff) eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
|
||||
else version_changed |= 0b01;
|
||||
}
|
||||
if (printer_type != PRINTER_TYPE) version_changed |= 0b10;
|
||||
if (motherboard != MOTHERBOARD) version_changed |= 0b01;
|
||||
return version_changed;
|
||||
}
|
||||
|
||||
|
|
@ -6463,10 +6453,9 @@ Sigma_Exit:
|
|||
SERIAL_ECHOPGM(" based on Marlin FIRMWARE_URL:https://github.com/prusa3d/Prusa-Firmware PROTOCOL_VERSION:");
|
||||
SERIAL_ECHOPGM(PROTOCOL_VERSION);
|
||||
SERIAL_ECHOPGM(" MACHINE_TYPE:");
|
||||
SERIAL_ECHOPGM(CUSTOM_MENDEL_NAME);
|
||||
SERIAL_ECHOPGM(" EXTRUDER_COUNT:");
|
||||
SERIAL_ECHOPGM(STRINGIFY(EXTRUDERS));
|
||||
SERIAL_ECHOPGM(" UUID:");
|
||||
SERIAL_ECHOPGM(CUSTOM_MENDEL_NAME);
|
||||
SERIAL_ECHOPGM(" EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS));
|
||||
SERIAL_ECHOPGM(" UUID:");
|
||||
SERIAL_ECHOLNPGM(MACHINE_UUID);
|
||||
#ifdef EXTENDED_CAPABILITIES_REPORT
|
||||
extended_capabilities_report();
|
||||
|
|
@ -7507,7 +7496,7 @@ Sigma_Exit:
|
|||
{
|
||||
lang_reset();
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_PROTOCOLPGM(("LANG SEL FORCED"));
|
||||
SERIAL_PROTOCOLPGM("LANG SEL FORCED");
|
||||
}
|
||||
break;
|
||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
|
@ -9143,11 +9132,10 @@ void update_currents() {
|
|||
#endif //MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
|
||||
|
||||
void get_coordinates() {
|
||||
bool seen[4]={false,false,false,false};
|
||||
for(int8_t i=0; i < NUM_AXIS; i++) {
|
||||
for (uint8_t i = X_AXIS, mask = X_AXIS_MASK; i < NUM_AXIS; i++, mask <<= 1) {
|
||||
if(code_seen(axis_codes[i]))
|
||||
{
|
||||
bool relative = axis_relative_modes & (1 << i);
|
||||
bool relative = axis_relative_modes & mask;
|
||||
destination[i] = code_value();
|
||||
if (i == E_AXIS) {
|
||||
float emult = extruder_multiplier[active_extruder];
|
||||
|
|
@ -9161,7 +9149,6 @@ void get_coordinates() {
|
|||
}
|
||||
if (relative)
|
||||
destination[i] += current_position[i];
|
||||
seen[i]=true;
|
||||
#if MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
|
||||
if (i == Z_AXIS && SilentModeMenu == SILENT_MODE_AUTO) update_currents();
|
||||
#endif //MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
|
||||
|
|
@ -9171,11 +9158,6 @@ void get_coordinates() {
|
|||
if(code_seen('F')) {
|
||||
next_feedrate = code_value();
|
||||
if(next_feedrate > 0.0) feedrate = next_feedrate;
|
||||
if (!seen[0] && !seen[1] && !seen[2] && seen[3])
|
||||
{
|
||||
// float e_max_speed =
|
||||
// printf_P(PSTR("E MOVE speed %7.3f\n"), feedrate / 60)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -11141,11 +11123,11 @@ void restore_extruder_temperature_from_ram() {
|
|||
//! @param e_move
|
||||
void restore_print_from_ram_and_continue(float e_move)
|
||||
{
|
||||
if (!saved_printing) return;
|
||||
|
||||
if (!saved_printing) return;
|
||||
|
||||
#ifdef FANCHECK
|
||||
// Do not allow resume printing if fans are still not ok
|
||||
if ((fan_check_error != EFCE_OK) && (fan_check_error != EFCE_FIXED)) return;
|
||||
// Do not allow resume printing if fans are still not ok
|
||||
if (fan_check_error == EFCE_REPORTED) return;
|
||||
if (fan_check_error == EFCE_FIXED) fan_check_error = EFCE_OK; //reenable serial stream processing if printing from usb
|
||||
#endif
|
||||
|
||||
|
|
|
|||
|
|
@ -7,7 +7,6 @@
|
|||
#include "stepper.h"
|
||||
#include "ultralcd.h"
|
||||
#include <avr/pgmspace.h>
|
||||
#include <ctype.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
|
||||
|
|
@ -80,8 +79,8 @@ void TCodes(char *const strchr_pointer, uint8_t codeValue) {
|
|||
}
|
||||
}
|
||||
} else {
|
||||
SERIAL_ECHO_START;
|
||||
if (selectedSlot.slot >= EXTRUDERS) {
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHO('T');
|
||||
SERIAL_ECHOLN(selectedSlot.slot + '0');
|
||||
SERIAL_ECHOLNRPGM(_n("Invalid extruder")); ////MSG_INVALID_EXTRUDER
|
||||
|
|
@ -92,9 +91,7 @@ void TCodes(char *const strchr_pointer, uint8_t codeValue) {
|
|||
// feedrate = next_feedrate;
|
||||
// }
|
||||
// }
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(_n("Active Extruder: ")); ////MSG_ACTIVE_EXTRUDER
|
||||
SERIAL_ECHOLN(active_extruder + '0'); // this is not changed in our FW at all, can be optimized away
|
||||
SERIAL_ECHORPGM(_n("Active Extruder: 0")); ////MSG_ACTIVE_EXTRUDER
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -220,6 +220,7 @@ void checkExtruderAutoFans()
|
|||
|
||||
#if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
|
||||
void readFanTach() {
|
||||
static bool fan_state[2];
|
||||
#ifdef FAN_SOFT_PWM
|
||||
if (READ(TACH_0) != fan_state[0]) {
|
||||
if(fan_measuring) fan_edge_counter[0] ++;
|
||||
|
|
|
|||
|
|
@ -159,8 +159,7 @@ static char menu_selection_mark(){
|
|||
|
||||
static void menu_draw_item_puts_P(char type_char, const char* str)
|
||||
{
|
||||
lcd_set_cursor(0, menu_row);
|
||||
lcd_putc(menu_selection_mark());
|
||||
lcd_putc_at(0, menu_row, menu_selection_mark());
|
||||
lcd_print_pad_P(str, LCD_WIDTH - 2);
|
||||
lcd_putc(type_char);
|
||||
}
|
||||
|
|
@ -218,10 +217,9 @@ void menu_format_sheet_select_E(const Sheet &sheet_E, SheetFormatBuffer &buffer)
|
|||
|
||||
static void menu_draw_item_select_sheet_E(char type_char, const Sheet &sheet)
|
||||
{
|
||||
lcd_set_cursor(0, menu_row);
|
||||
SheetFormatBuffer buffer;
|
||||
menu_format_sheet_select_E(sheet, buffer);
|
||||
lcd_putc(menu_selection_mark());
|
||||
lcd_putc_at(0, menu_row, menu_selection_mark());
|
||||
lcd_print_pad(buffer.c, LCD_WIDTH - 2);
|
||||
lcd_putc(type_char);
|
||||
}
|
||||
|
|
@ -229,10 +227,9 @@ static void menu_draw_item_select_sheet_E(char type_char, const Sheet &sheet)
|
|||
|
||||
static void menu_draw_item_puts_E(char type_char, const Sheet &sheet)
|
||||
{
|
||||
lcd_set_cursor(0, menu_row);
|
||||
SheetFormatBuffer buffer;
|
||||
menu_format_sheet_E(sheet, buffer);
|
||||
lcd_putc(menu_selection_mark());
|
||||
lcd_putc_at(0, menu_row, menu_selection_mark());
|
||||
lcd_print_pad(buffer.c, LCD_WIDTH - 2);
|
||||
lcd_putc(type_char);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -705,9 +705,8 @@ void ProtocolLogic::FormatLastResponseMsgAndClearLRB(char *dst) {
|
|||
*dst++ = '<';
|
||||
for (uint8_t i = 0; i < lrb; ++i) {
|
||||
uint8_t b = lastReceivedBytes[i];
|
||||
if (b < 32)
|
||||
b = '.';
|
||||
if (b > 127)
|
||||
// Check for printable character, including space
|
||||
if (b < 32 || b > 127)
|
||||
b = '.';
|
||||
*dst++ = b;
|
||||
}
|
||||
|
|
@ -721,9 +720,8 @@ void ProtocolLogic::LogRequestMsg(const uint8_t *txbuff, uint8_t size) {
|
|||
static char lastMsg[rqs] = "";
|
||||
for (uint8_t i = 0; i < size; ++i) {
|
||||
uint8_t b = txbuff[i];
|
||||
if (b < 32)
|
||||
b = '.';
|
||||
if (b > 127)
|
||||
// Check for printable character, including space
|
||||
if (b < 32 || b > 127)
|
||||
b = '.';
|
||||
tmp[i + 1] = b;
|
||||
}
|
||||
|
|
|
|||
|
|
@ -2261,7 +2261,7 @@ static void check_min_temp_raw()
|
|||
if(target_temperature_isr[active_extruder]>minttemp[active_extruder]) {
|
||||
// ~ nozzle heating is on
|
||||
bCheckingOnHeater=bCheckingOnHeater||(current_temperature_isr[active_extruder]>(minttemp[active_extruder]+TEMP_HYSTERESIS)); // for eventually delay cutting
|
||||
if(oTimer4minTempHeater.expired(HEATER_MINTEMP_DELAY)||(!oTimer4minTempHeater.running())||bCheckingOnHeater) {
|
||||
if(oTimer4minTempHeater.expired_cont(HEATER_MINTEMP_DELAY) || bCheckingOnHeater) {
|
||||
bCheckingOnHeater=true; // not necessary
|
||||
check_min_temp_heater0(); // delay is elapsed or temperature is/was over minTemp => periodical checking is active
|
||||
}
|
||||
|
|
@ -2275,7 +2275,7 @@ static void check_min_temp_raw()
|
|||
if(target_temperature_bed_isr>BED_MINTEMP) {
|
||||
// ~ bed heating is on
|
||||
bCheckingOnBed=bCheckingOnBed||(current_temperature_bed_isr>(BED_MINTEMP+TEMP_HYSTERESIS)); // for eventually delay cutting
|
||||
if(oTimer4minTempBed.expired(BED_MINTEMP_DELAY)||(!oTimer4minTempBed.running())||bCheckingOnBed) {
|
||||
if(oTimer4minTempBed.expired_cont(BED_MINTEMP_DELAY) || bCheckingOnBed) {
|
||||
bCheckingOnBed=true; // not necessary
|
||||
check_min_temp_bed(); // delay is elapsed or temperature is/was over minTemp => periodical checking is active
|
||||
}
|
||||
|
|
|
|||
|
|
@ -23,32 +23,32 @@ uint8_t tmc2130_current_h[4] = TMC2130_CURRENTS_H;
|
|||
uint8_t tmc2130_current_r[4] = TMC2130_CURRENTS_R;
|
||||
|
||||
//running currents for homing
|
||||
uint8_t tmc2130_current_r_home[4] = TMC2130_CURRENTS_R_HOME;
|
||||
static uint8_t tmc2130_current_r_home[4] = TMC2130_CURRENTS_R_HOME;
|
||||
|
||||
|
||||
//pwm_ampl
|
||||
uint8_t tmc2130_pwm_ampl[4] = {TMC2130_PWM_AMPL_X, TMC2130_PWM_AMPL_Y, TMC2130_PWM_AMPL_Z, TMC2130_PWM_AMPL_E};
|
||||
static uint8_t tmc2130_pwm_ampl[4] = {TMC2130_PWM_AMPL_X, TMC2130_PWM_AMPL_Y, TMC2130_PWM_AMPL_Z, TMC2130_PWM_AMPL_E};
|
||||
//pwm_grad
|
||||
uint8_t tmc2130_pwm_grad[4] = {TMC2130_PWM_GRAD_X, TMC2130_PWM_GRAD_Y, TMC2130_PWM_GRAD_Z, TMC2130_PWM_GRAD_E};
|
||||
static uint8_t tmc2130_pwm_grad[4] = {TMC2130_PWM_GRAD_X, TMC2130_PWM_GRAD_Y, TMC2130_PWM_GRAD_Z, TMC2130_PWM_GRAD_E};
|
||||
//pwm_auto
|
||||
uint8_t tmc2130_pwm_auto[4] = {TMC2130_PWM_AUTO_X, TMC2130_PWM_AUTO_Y, TMC2130_PWM_AUTO_Z, TMC2130_PWM_AUTO_E};
|
||||
static uint8_t tmc2130_pwm_auto[4] = {TMC2130_PWM_AUTO_X, TMC2130_PWM_AUTO_Y, TMC2130_PWM_AUTO_Z, TMC2130_PWM_AUTO_E};
|
||||
//pwm_freq
|
||||
uint8_t tmc2130_pwm_freq[4] = {TMC2130_PWM_FREQ_X, TMC2130_PWM_FREQ_Y, TMC2130_PWM_FREQ_Z, TMC2130_PWM_FREQ_E};
|
||||
static uint8_t tmc2130_pwm_freq[4] = {TMC2130_PWM_FREQ_X, TMC2130_PWM_FREQ_Y, TMC2130_PWM_FREQ_Z, TMC2130_PWM_FREQ_E};
|
||||
|
||||
uint8_t tmc2130_mres[4] = {0, 0, 0, 0}; //will be filed at begin of init
|
||||
|
||||
|
||||
uint8_t tmc2130_sg_thr[4] = {TMC2130_SG_THRS_X, TMC2130_SG_THRS_Y, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E};
|
||||
uint8_t tmc2130_sg_thr_home[4] = TMC2130_SG_THRS_HOME;
|
||||
static uint8_t tmc2130_sg_thr_home[4] = TMC2130_SG_THRS_HOME;
|
||||
|
||||
|
||||
uint8_t tmc2130_sg_homing_axes_mask = 0x00;
|
||||
|
||||
const char eMotorCurrentScalingEnabled[] PROGMEM = "E-motor current scaling enabled";
|
||||
|
||||
uint8_t tmc2130_sg_measure = 0xff;
|
||||
uint32_t tmc2130_sg_measure_cnt = 0;
|
||||
uint32_t tmc2130_sg_measure_val = 0;
|
||||
static uint8_t tmc2130_sg_measure = 0xff;
|
||||
static uint32_t tmc2130_sg_measure_cnt = 0;
|
||||
static uint32_t tmc2130_sg_measure_val = 0;
|
||||
|
||||
uint8_t tmc2130_home_enabled = 0;
|
||||
uint8_t tmc2130_home_origin[2] = {0, 0};
|
||||
|
|
@ -65,11 +65,10 @@ tmc2130_chopper_config_t tmc2130_chopper_config[4] = {
|
|||
};
|
||||
|
||||
bool tmc2130_sg_stop_on_crash = true;
|
||||
uint8_t tmc2130_sg_diag_mask = 0x00;
|
||||
uint8_t tmc2130_sg_crash = 0;
|
||||
|
||||
//used for triggering a periodic check (1s) of the overtemperature pre-warning flag at ~120C (+-20C)
|
||||
ShortTimer tmc2130_overtemp_timer;
|
||||
static ShortTimer tmc2130_overtemp_timer;
|
||||
|
||||
#define DBG(args...)
|
||||
//printf_P(args)
|
||||
|
|
@ -358,7 +357,7 @@ bool tmc2130_wait_standstill_xy(int timeout)
|
|||
|
||||
void tmc2130_check_overtemp()
|
||||
{
|
||||
if (tmc2130_overtemp_timer.expired(1000) || !tmc2130_overtemp_timer.running())
|
||||
if (tmc2130_overtemp_timer.expired_cont(1000))
|
||||
{
|
||||
for (uint_least8_t i = 0; i < 4; i++)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -16,10 +16,6 @@ extern uint8_t tmc2130_sg_thr[4];
|
|||
extern bool tmc2130_sg_stop_on_crash;
|
||||
extern uint8_t tmc2130_sg_crash; //crash mask
|
||||
|
||||
extern uint8_t tmc2130_sg_measure;
|
||||
extern uint32_t tmc2130_sg_measure_cnt;
|
||||
extern uint32_t tmc2130_sg_measure_val;
|
||||
|
||||
extern uint8_t tmc2130_sg_homing_axes_mask;
|
||||
|
||||
extern const char eMotorCurrentScalingEnabled[];
|
||||
|
|
|
|||
|
|
@ -50,7 +50,6 @@
|
|||
|
||||
#include "Prusa_farm.h"
|
||||
|
||||
int clock_interval = 0;
|
||||
static void lcd_sd_updir();
|
||||
static void lcd_mesh_bed_leveling_settings();
|
||||
#ifdef LCD_BL_PIN
|
||||
|
|
@ -67,8 +66,6 @@ uint8_t scrollstuff = 0;
|
|||
|
||||
int8_t SilentModeMenu = SILENT_MODE_OFF;
|
||||
|
||||
int8_t FSensorStateMenu = 1;
|
||||
|
||||
LcdCommands lcd_commands_type = LcdCommands::Idle;
|
||||
static uint8_t lcd_commands_step = 0;
|
||||
static bool extraPurgeNeeded = false; ///< lcd_commands - detect if extra purge after MMU-toolchange is necessary or not
|
||||
|
|
@ -270,22 +267,18 @@ const char STR_SEPARATOR[] PROGMEM = "------------";
|
|||
static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* longFilename)
|
||||
{
|
||||
uint8_t len = LCD_WIDTH - 1;
|
||||
lcd_set_cursor(0, row);
|
||||
lcd_print((lcd_encoder == menu_item)?'>':' ');
|
||||
lcd_putc_at(0, row, (lcd_encoder == menu_item)?'>':' ');
|
||||
lcd_print_pad(longFilename, len);
|
||||
}
|
||||
|
||||
static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* longFilename)
|
||||
{
|
||||
uint8_t len = LCD_WIDTH - 2;
|
||||
lcd_set_cursor(0, row);
|
||||
lcd_print((lcd_encoder == menu_item)?'>':' ');
|
||||
lcd_print(LCD_STR_FOLDER[0]);
|
||||
lcd_putc_at(0, row, (lcd_encoder == menu_item)?'>':' ');
|
||||
lcd_putc(LCD_STR_FOLDER[0]);
|
||||
lcd_print_pad(longFilename, len);
|
||||
}
|
||||
|
||||
|
||||
|
||||
#define MENU_ITEM_SDDIR(str_fn, str_fnl) do { menu_item_sddir(str_fn, str_fnl); } while (0)
|
||||
#define MENU_ITEM_SDFILE(str_fn, str_fnl) do { menu_item_sdfile(str_fn, str_fnl); } while (0)
|
||||
|
||||
|
|
@ -453,6 +446,7 @@ void lcdui_print_cmd_diag(void)
|
|||
// Print time (8 chars total)
|
||||
void lcdui_print_time(void)
|
||||
{
|
||||
static uint8_t clock_interval; // max value is 10: CLOCK_INTERVAL_TIME * 2
|
||||
//if remaining print time estimation is available print it else print elapsed time
|
||||
int chars = 0;
|
||||
if (printer_active()) {
|
||||
|
|
@ -516,6 +510,7 @@ void lcdui_print_time(void)
|
|||
|
||||
//! @Brief Print status line on status screen
|
||||
void lcdui_print_status_line(void) {
|
||||
static uint8_t heating_status_counter;
|
||||
if (heating_status != HeatingStatus::NO_HEATING) { // If heating flag, show progress of heating
|
||||
heating_status_counter++;
|
||||
if (heating_status_counter > 13) {
|
||||
|
|
@ -2748,10 +2743,9 @@ bool lcd_wait_for_pinda(float temp) {
|
|||
while (current_temperature_pinda > temp){
|
||||
lcd_display_message_fullscreen_P(_i("Waiting for PINDA probe cooling"));////MSG_WAITING_TEMP_PINDA c=20 r=3
|
||||
|
||||
lcd_set_cursor(0, 4);
|
||||
lcd_print(LCD_STR_THERMOMETER[0]);
|
||||
lcd_putc_at(0, 4, LCD_STR_THERMOMETER[0]);
|
||||
lcd_printf_P(PSTR("%3d/%3d"), (int16_t)current_temperature_pinda, (int16_t) temp);
|
||||
lcd_print(LCD_STR_DEGREE[0]);
|
||||
lcd_putc(LCD_STR_DEGREE[0]);
|
||||
delay_keep_alive(1000);
|
||||
serialecho_temperatures();
|
||||
if (pinda_timeout.expired(8 * 60 * 1000ul)) { //PINDA cooling from 60 C to 35 C takes about 7 minutes
|
||||
|
|
@ -2766,10 +2760,9 @@ bool lcd_wait_for_pinda(float temp) {
|
|||
|
||||
void lcd_wait_for_heater() {
|
||||
lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING));
|
||||
lcd_set_cursor(0, 4);
|
||||
lcd_print(LCD_STR_THERMOMETER[0]);
|
||||
lcd_putc_at(0, 4, LCD_STR_THERMOMETER[0]);
|
||||
lcd_printf_P(PSTR("%3d/%3d"), (int16_t)degHotend(active_extruder), (int16_t) degTargetHotend(active_extruder));
|
||||
lcd_print(LCD_STR_DEGREE[0]);
|
||||
lcd_putc(LCD_STR_DEGREE[0]);
|
||||
}
|
||||
|
||||
void lcd_wait_for_cool_down() {
|
||||
|
|
@ -2780,15 +2773,13 @@ void lcd_wait_for_cool_down() {
|
|||
while ((degHotend(0)>MAX_HOTEND_TEMP_CALIBRATION) || (degBed() > MAX_BED_TEMP_CALIBRATION)) {
|
||||
lcd_display_message_fullscreen_P(_i("Waiting for nozzle and bed cooling"));////MSG_WAITING_TEMP c=20 r=4
|
||||
|
||||
lcd_set_cursor(0, 4);
|
||||
lcd_print(LCD_STR_THERMOMETER[0]);
|
||||
lcd_putc_at(0, 4, LCD_STR_THERMOMETER[0]);
|
||||
lcd_printf_P(PSTR("%3d/0"), (int16_t)degHotend(0));
|
||||
lcd_print(LCD_STR_DEGREE[0]);
|
||||
lcd_putc(LCD_STR_DEGREE[0]);
|
||||
|
||||
lcd_set_cursor(9, 4);
|
||||
lcd_print(LCD_STR_BEDTEMP[0]);
|
||||
lcd_putc_at(9, 4, LCD_STR_BEDTEMP[0]);
|
||||
lcd_printf_P(PSTR("%3d/0"), (int16_t)degBed());
|
||||
lcd_print(LCD_STR_DEGREE[0]);
|
||||
lcd_putc(LCD_STR_DEGREE[0]);
|
||||
delay_keep_alive(1000);
|
||||
serialecho_temperatures();
|
||||
}
|
||||
|
|
@ -2940,9 +2931,8 @@ static const char* lcd_display_message_fullscreen_nonBlocking_P(const char *msg)
|
|||
if (multi_screen) {
|
||||
// Display the "next screen" indicator character.
|
||||
lcd_set_custom_characters_nextpage();
|
||||
lcd_set_cursor(19, 3);
|
||||
// Display the double down arrow.
|
||||
lcd_print(LCD_STR_ARROW_2_DOWN[0]);
|
||||
lcd_putc_at(19, 3, LCD_STR_ARROW_2_DOWN[0]);
|
||||
}
|
||||
|
||||
return multi_screen ? msgend : NULL;
|
||||
|
|
@ -2974,9 +2964,8 @@ void lcd_show_fullscreen_message_and_wait_P(const char *msg)
|
|||
// Until confirmed by a button click.
|
||||
for (;;) {
|
||||
if (msg_next == NULL) {
|
||||
lcd_set_cursor(19, 3);
|
||||
// Display the confirm char.
|
||||
lcd_print(LCD_STR_CONFIRM[0]);
|
||||
lcd_putc_at(19, 3, LCD_STR_CONFIRM[0]);
|
||||
}
|
||||
// Wait for 5 seconds before displaying the next text.
|
||||
for (uint8_t i = 0; i < 100; ++ i) {
|
||||
|
|
@ -3228,17 +3217,16 @@ void lcd_temp_cal_show_result(bool result) {
|
|||
disable_e2();
|
||||
setTargetBed(0); //set bed target temperature back to 0
|
||||
|
||||
if (result == true) {
|
||||
eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 1);
|
||||
// Store boolean result
|
||||
eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, result);
|
||||
eeprom_update_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE, result);
|
||||
|
||||
if (result) {
|
||||
SERIAL_ECHOLNPGM("PINDA calibration done. Continue with pressing the knob.");
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_PINDA_CALIBRATION_DONE));
|
||||
eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 1);
|
||||
}
|
||||
else {
|
||||
eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0);
|
||||
} else {
|
||||
SERIAL_ECHOLNPGM("PINDA calibration failed. Continue with pressing the knob.");
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("PINDA calibration failed"));////MSG_PINDA_CAL_FAILED c=20 r=4
|
||||
eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 0);
|
||||
}
|
||||
lcd_update_enable(true);
|
||||
lcd_update(2);
|
||||
|
|
@ -3303,20 +3291,15 @@ static void lcd_show_sensors_state()
|
|||
{
|
||||
//0: N/A; 1: OFF; 2: ON
|
||||
uint8_t pinda_state = STATE_NA;
|
||||
uint8_t finda_state = STATE_NA;
|
||||
uint8_t idler_state = STATE_NA;
|
||||
|
||||
pinda_state = READ(Z_MIN_PIN);
|
||||
if (MMU2::mmu2.Enabled())
|
||||
{
|
||||
finda_state = MMU2::mmu2.FindaDetectsFilament();
|
||||
}
|
||||
lcd_puts_at_P(0, 0, MSG_PINDA);
|
||||
lcd_set_cursor(LCD_WIDTH - 14, 0);
|
||||
lcd_print_state(pinda_state);
|
||||
|
||||
if (MMU2::mmu2.Enabled())
|
||||
{
|
||||
if (MMU2::mmu2.Enabled()) {
|
||||
const uint8_t finda_state = MMU2::mmu2.FindaDetectsFilament();
|
||||
lcd_puts_at_P(10, 0, _n("FINDA"));////MSG_FINDA c=5
|
||||
lcd_set_cursor(LCD_WIDTH - 3, 0);
|
||||
lcd_print_state(finda_state);
|
||||
|
|
@ -4796,8 +4779,7 @@ char reset_menu() {
|
|||
};
|
||||
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 0);
|
||||
lcd_putc('>');
|
||||
lcd_putc_at(0, 0, '>');
|
||||
lcd_consume_click();
|
||||
while (1) {
|
||||
|
||||
|
|
@ -5150,8 +5132,7 @@ static void lcd_rename_sheet_menu()
|
|||
{
|
||||
lcd_putc(menuData->name[i]);
|
||||
}
|
||||
lcd_set_cursor(menuData->selected, 1);
|
||||
lcd_putc('^');
|
||||
lcd_putc_at(menuData->selected, 1, '^');
|
||||
if (lcd_clicked())
|
||||
{
|
||||
if ((menuData->selected + 1u) < sizeof(Sheet::name))
|
||||
|
|
@ -5294,7 +5275,7 @@ static void lcd_main_menu()
|
|||
// only allow resuming if hardware errors (temperature or fan) are cleared
|
||||
if(!get_temp_error()
|
||||
#ifdef FANCHECK
|
||||
&& ((fan_check_error == EFCE_FIXED) || (fan_check_error == EFCE_OK))
|
||||
&& fan_check_error != EFCE_REPORTED
|
||||
#endif //FANCHECK
|
||||
) {
|
||||
if (saved_printing) {
|
||||
|
|
@ -5891,8 +5872,7 @@ void lcd_sdcard_menu()
|
|||
if (_md->lcd_scrollTimer.expired(300) || rewindFlag)
|
||||
{
|
||||
uint8_t len = LCD_WIDTH - ((_md->isDir)? 2 : 1);
|
||||
lcd_set_cursor(0, _md->row);
|
||||
lcd_print('>');
|
||||
lcd_putc_at(0, _md->row, '>');
|
||||
if (_md->isDir)
|
||||
lcd_print(LCD_STR_FOLDER[0]);
|
||||
|
||||
|
|
@ -5929,7 +5909,7 @@ void lcd_belttest()
|
|||
|
||||
uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
|
||||
uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
|
||||
lcd_printf_P(_T(MSG_CHECKING_X));
|
||||
lcd_puts_P(_T(MSG_CHECKING_X));
|
||||
lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %u -> ..."),X);
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
|
|
@ -5937,15 +5917,16 @@ void lcd_belttest()
|
|||
// that clobbers ours, with more info than we could provide. So on fail we just fall through to take us back to status.
|
||||
if (lcd_selfcheck_axis_sg(X_AXIS)){
|
||||
X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
|
||||
lcd_set_cursor(10,1), lcd_printf_P(PSTR("%u"),X); // Show new X value next to old one.
|
||||
lcd_puts_at_P(0,2,_T(MSG_CHECKING_Y));
|
||||
lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %u -> ..."),Y);
|
||||
lcd_set_cursor(10, 1);
|
||||
lcd_print(X); // Show new X value next to old one.
|
||||
lcd_puts_at_P(0, 2, _T(MSG_CHECKING_Y));
|
||||
lcd_set_cursor(0, 3), lcd_printf_P(PSTR("Y: %u -> ..."),Y);
|
||||
if (lcd_selfcheck_axis_sg(Y_AXIS))
|
||||
{
|
||||
Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
|
||||
lcd_set_cursor(10,3),lcd_printf_P(PSTR("%u"),Y);
|
||||
lcd_set_cursor(19, 3);
|
||||
lcd_print(LCD_STR_UPLEVEL[0]);
|
||||
lcd_set_cursor(10, 3);
|
||||
lcd_print(Y);
|
||||
lcd_putc_at(19, 3, LCD_STR_UPLEVEL[0]);
|
||||
lcd_wait_for_click_delay(10);
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -125,7 +125,6 @@ enum class LcdCommands : uint_least8_t
|
|||
};
|
||||
|
||||
extern LcdCommands lcd_commands_type;
|
||||
extern int8_t FSensorStateMenu;
|
||||
|
||||
enum class CustomMsg : uint_least8_t
|
||||
{
|
||||
|
|
@ -164,7 +163,6 @@ void printf_IRSensorAnalogBoardChange();
|
|||
|
||||
extern int8_t SilentModeMenu;
|
||||
|
||||
extern bool cancel_heatup;
|
||||
extern bool isPrintPaused;
|
||||
|
||||
extern uint8_t scrollstuff;
|
||||
|
|
|
|||
|
|
@ -240,43 +240,26 @@ void update_current_firmware_version_to_eeprom()
|
|||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_FLAVOR, (uint16_t)pgm_read_word(&FW_VERSION_NR[3]));
|
||||
}
|
||||
|
||||
ClNozzleDiameter oNozzleDiameter=ClNozzleDiameter::_Diameter_400;
|
||||
ClCheckMode oCheckMode=ClCheckMode::_None;
|
||||
ClCheckModel oCheckModel=ClCheckModel::_None;
|
||||
ClCheckVersion oCheckVersion=ClCheckVersion::_None;
|
||||
ClCheckGcode oCheckGcode=ClCheckGcode::_None;
|
||||
ClNozzleDiameter oNozzleDiameter;
|
||||
ClCheckMode oCheckMode;
|
||||
ClCheckModel oCheckModel;
|
||||
ClCheckVersion oCheckVersion;
|
||||
ClCheckGcode oCheckGcode;
|
||||
|
||||
void fCheckModeInit() {
|
||||
oCheckMode = (ClCheckMode)eeprom_read_byte((uint8_t *)EEPROM_CHECK_MODE);
|
||||
if (oCheckMode == ClCheckMode::_Undef) {
|
||||
oCheckMode = ClCheckMode::_Warn;
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CHECK_MODE, (uint8_t)oCheckMode);
|
||||
}
|
||||
oCheckMode = (ClCheckMode)eeprom_init_default_byte((uint8_t *)EEPROM_CHECK_MODE, (uint8_t)ClCheckMode::_Warn);
|
||||
|
||||
if (farm_mode) {
|
||||
oCheckMode = ClCheckMode::_Strict;
|
||||
eeprom_init_default_word((uint16_t *)EEPROM_NOZZLE_DIAMETER_uM, EEPROM_NOZZLE_DIAMETER_uM_DEFAULT);
|
||||
}
|
||||
oNozzleDiameter = (ClNozzleDiameter)eeprom_read_byte((uint8_t *)EEPROM_NOZZLE_DIAMETER);
|
||||
if ((oNozzleDiameter == ClNozzleDiameter::_Diameter_Undef) && !farm_mode) {
|
||||
oNozzleDiameter = ClNozzleDiameter::_Diameter_400;
|
||||
eeprom_update_byte((uint8_t *)EEPROM_NOZZLE_DIAMETER, (uint8_t)oNozzleDiameter);
|
||||
eeprom_update_word((uint16_t *)EEPROM_NOZZLE_DIAMETER_uM, EEPROM_NOZZLE_DIAMETER_uM_DEFAULT);
|
||||
}
|
||||
oCheckModel = (ClCheckModel)eeprom_read_byte((uint8_t *)EEPROM_CHECK_MODEL);
|
||||
if (oCheckModel == ClCheckModel::_Undef) {
|
||||
oCheckModel = ClCheckModel::_Warn;
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CHECK_MODEL, (uint8_t)oCheckModel);
|
||||
}
|
||||
oCheckVersion = (ClCheckVersion)eeprom_read_byte((uint8_t *)EEPROM_CHECK_VERSION);
|
||||
if (oCheckVersion == ClCheckVersion::_Undef) {
|
||||
oCheckVersion = ClCheckVersion::_Warn;
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CHECK_VERSION, (uint8_t)oCheckVersion);
|
||||
}
|
||||
oCheckGcode = (ClCheckGcode)eeprom_read_byte((uint8_t *)EEPROM_CHECK_GCODE);
|
||||
if (oCheckGcode == ClCheckGcode::_Undef) {
|
||||
oCheckGcode = ClCheckGcode::_Warn;
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CHECK_GCODE, (uint8_t)oCheckGcode);
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CHECK_MODE, (uint8_t)ClCheckMode::_Strict);
|
||||
}
|
||||
|
||||
oNozzleDiameter = (ClNozzleDiameter)eeprom_init_default_byte((uint8_t *)EEPROM_NOZZLE_DIAMETER, (uint8_t)ClNozzleDiameter::_Diameter_400);
|
||||
eeprom_init_default_word((uint16_t *)EEPROM_NOZZLE_DIAMETER_uM, EEPROM_NOZZLE_DIAMETER_uM_DEFAULT);
|
||||
|
||||
oCheckModel = (ClCheckModel)eeprom_init_default_byte((uint8_t *)EEPROM_CHECK_MODEL, (uint8_t)ClCheckModel::_Warn);
|
||||
oCheckVersion = (ClCheckVersion)eeprom_init_default_byte((uint8_t *)EEPROM_CHECK_VERSION, (uint8_t)ClCheckVersion::_Warn);
|
||||
oCheckGcode = (ClCheckGcode)eeprom_init_default_byte((uint8_t *)EEPROM_CHECK_GCODE, (uint8_t)ClCheckGcode::_Warn);
|
||||
}
|
||||
|
||||
static void render_M862_warnings(const char* warning, const char* strict, uint8_t check)
|
||||
|
|
|
|||
Loading…
Reference in New Issue