Merge branch 'MK3' into MK3_NEW_SD_COMPILATION
This commit is contained in:
commit
0e25eaee8f
|
|
@ -152,7 +152,6 @@
|
|||
#define Z_HOME_RETRACT_MM 2
|
||||
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
|
||||
|
||||
#define AXIS_RELATIVE_MODES {0, 0, 0, 0}
|
||||
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step). Toshiba steppers are 4x slower, but Prusa3D does not use those.
|
||||
//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
|
||||
#define INVERT_X_STEP_PIN 0
|
||||
|
|
|
|||
|
|
@ -1,5 +1,6 @@
|
|||
#include "Dcodes.h"
|
||||
//#include "Marlin.h"
|
||||
#include "Configuration.h"
|
||||
#include "language.h"
|
||||
#include "cmdqueue.h"
|
||||
#include <stdio.h>
|
||||
|
|
@ -97,7 +98,7 @@ void print_mem(uint32_t address, uint16_t count, uint8_t type, uint8_t countperl
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef DEBUG_DCODE3
|
||||
#if defined DEBUG_DCODE3 || defined DEBUG_DCODES
|
||||
#define EEPROM_SIZE 0x1000
|
||||
/*!
|
||||
### D3 - Read/Write EEPROM <a href="https://reprap.org/wiki/G-code#D3:_Read.2FWrite_EEPROM">D3: Read/Write EEPROM</a>
|
||||
|
|
@ -185,7 +186,6 @@ void dcode_3()
|
|||
#define BOOT_APP_FLG_COPY 0x02
|
||||
#define BOOT_APP_FLG_FLASH 0x04
|
||||
|
||||
extern uint8_t fsensor_log;
|
||||
extern float current_temperature_pinda;
|
||||
extern float axis_steps_per_unit[NUM_AXIS];
|
||||
|
||||
|
|
@ -360,7 +360,7 @@ void dcode_4()
|
|||
}
|
||||
#endif //DEBUG_DCODES
|
||||
|
||||
#ifdef DEBUG_DCODE5
|
||||
#if defined DEBUG_DCODE5 || defined DEBUG_DCODES
|
||||
|
||||
/*!
|
||||
### D5 - Read/Write FLASH <a href="https://reprap.org/wiki/G-code#D5:_Read.2FWrite_FLASH">D5: Read/Write Flash</a>
|
||||
|
|
@ -372,7 +372,7 @@ void dcode_4()
|
|||
#### Parameters
|
||||
- `A` - Address (x00000-x3ffff)
|
||||
- `C` - Count (1-8192)
|
||||
- `X` - Data
|
||||
- `X` - Data (hex)
|
||||
- `E` - Erase
|
||||
|
||||
#### Notes
|
||||
|
|
@ -635,6 +635,98 @@ void dcode_12()
|
|||
|
||||
}
|
||||
|
||||
#ifdef HEATBED_ANALYSIS
|
||||
/*!
|
||||
### D80 - Bed check <a href="https://reprap.org/wiki/G-code#D80:_Bed_check">D80: Bed check</a>
|
||||
This command will log data to SD card file "mesh.txt".
|
||||
#### Usage
|
||||
|
||||
D80 [ E | F | G | H | I | J ]
|
||||
|
||||
#### Parameters
|
||||
- `E` - Dimension X (default 40)
|
||||
- `F` - Dimention Y (default 40)
|
||||
- `G` - Points X (default 40)
|
||||
- `H` - Points Y (default 40)
|
||||
- `I` - Offset X (default 74)
|
||||
- `J` - Offset Y (default 34)
|
||||
*/
|
||||
void dcode_80()
|
||||
{
|
||||
float dimension_x = 40;
|
||||
float dimension_y = 40;
|
||||
int points_x = 40;
|
||||
int points_y = 40;
|
||||
float offset_x = 74;
|
||||
float offset_y = 33;
|
||||
|
||||
if (code_seen('E')) dimension_x = code_value();
|
||||
if (code_seen('F')) dimension_y = code_value();
|
||||
if (code_seen('G')) {points_x = code_value(); }
|
||||
if (code_seen('H')) {points_y = code_value(); }
|
||||
if (code_seen('I')) {offset_x = code_value(); }
|
||||
if (code_seen('J')) {offset_y = code_value(); }
|
||||
printf_P(PSTR("DIM X: %f\n"), dimension_x);
|
||||
printf_P(PSTR("DIM Y: %f\n"), dimension_y);
|
||||
printf_P(PSTR("POINTS X: %d\n"), points_x);
|
||||
printf_P(PSTR("POINTS Y: %d\n"), points_y);
|
||||
printf_P(PSTR("OFFSET X: %f\n"), offset_x);
|
||||
printf_P(PSTR("OFFSET Y: %f\n"), offset_y);
|
||||
bed_check(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
|
||||
}
|
||||
|
||||
|
||||
/*!
|
||||
### D81 - Bed analysis <a href="https://reprap.org/wiki/G-code#D81:_Bed_analysis">D80: Bed analysis</a>
|
||||
This command will log data to SD card file "wldsd.txt".
|
||||
#### Usage
|
||||
|
||||
D81 [ E | F | G | H | I | J ]
|
||||
|
||||
#### Parameters
|
||||
- `E` - Dimension X (default 40)
|
||||
- `F` - Dimention Y (default 40)
|
||||
- `G` - Points X (default 40)
|
||||
- `H` - Points Y (default 40)
|
||||
- `I` - Offset X (default 74)
|
||||
- `J` - Offset Y (default 34)
|
||||
*/
|
||||
void dcode_81()
|
||||
{
|
||||
float dimension_x = 40;
|
||||
float dimension_y = 40;
|
||||
int points_x = 40;
|
||||
int points_y = 40;
|
||||
float offset_x = 74;
|
||||
float offset_y = 33;
|
||||
|
||||
if (code_seen('E')) dimension_x = code_value();
|
||||
if (code_seen('F')) dimension_y = code_value();
|
||||
if (code_seen("G")) { strchr_pointer+=1; points_x = code_value(); }
|
||||
if (code_seen("H")) { strchr_pointer+=1; points_y = code_value(); }
|
||||
if (code_seen("I")) { strchr_pointer+=1; offset_x = code_value(); }
|
||||
if (code_seen("J")) { strchr_pointer+=1; offset_y = code_value(); }
|
||||
|
||||
bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
|
||||
|
||||
}
|
||||
|
||||
#endif //HEATBED_ANALYSIS
|
||||
|
||||
/*!
|
||||
### D106 - Print measured fan speed for different pwm values <a href="https://reprap.org/wiki/G-code#D106:_Print_measured_fan_speed_for_different_pwm_values">D106: Print measured fan speed for different pwm values</a>
|
||||
*/
|
||||
void dcode_106()
|
||||
{
|
||||
for (int i = 255; i > 0; i = i - 5) {
|
||||
fanSpeed = i;
|
||||
//delay_keep_alive(2000);
|
||||
for (int j = 0; j < 100; j++) {
|
||||
delay_keep_alive(100);
|
||||
}
|
||||
printf_P(_N("%d: %d\n"), i, fan_speed[1]);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef TMC2130
|
||||
#include "planner.h"
|
||||
|
|
@ -843,11 +935,13 @@ void dcode_9125()
|
|||
pat9125_y = (int)code_value();
|
||||
LOG("pat9125_y=%d\n", pat9125_y);
|
||||
}
|
||||
#ifdef DEBUG_FSENSOR_LOG
|
||||
if (code_seen('L'))
|
||||
{
|
||||
fsensor_log = (int)code_value();
|
||||
LOG("fsensor_log=%d\n", fsensor_log);
|
||||
}
|
||||
#endif //DEBUG_FSENSOR_LOG
|
||||
}
|
||||
#endif //PAT9125
|
||||
|
||||
|
|
|
|||
|
|
@ -2,26 +2,40 @@
|
|||
#define DCODES_H
|
||||
|
||||
extern void dcode__1(); //D-1 - Endless loop (to simulate deadlock)
|
||||
|
||||
extern void dcode_0(); //D0 - Reset
|
||||
extern void dcode_1(); //D1 - Clear EEPROM
|
||||
extern void dcode_2(); //D2 - Read/Write RAM
|
||||
|
||||
#if defined DEBUG_DCODE3 || defined DEBUG_DCODES
|
||||
extern void dcode_3(); //D3 - Read/Write EEPROM
|
||||
#endif //DEBUG_DCODE3
|
||||
|
||||
extern void dcode_4(); //D4 - Read/Write PIN
|
||||
|
||||
#if defined DEBUG_DCODE5 || defined DEBUG_DCODES
|
||||
extern void dcode_5(); //D5 - Read/Write FLASH
|
||||
#endif //DEBUG_DCODE5
|
||||
|
||||
extern void dcode_6(); //D6 - Read/Write external FLASH
|
||||
extern void dcode_7(); //D7 - Read/Write Bootloader
|
||||
extern void dcode_8(); //D8 - Read/Write PINDA
|
||||
extern void dcode_9(); //D9 - Read/Write ADC (Write=enable simulated, Read=disable simulated)
|
||||
|
||||
extern void dcode_10(); //D10 - XYZ calibration = OK
|
||||
extern void dcode_12(); //D12 - Log time. Writes the current time in the log file.
|
||||
|
||||
#ifdef HEATBED_ANALYSIS
|
||||
extern void dcode_80(); //D80 - Bed check. This command will log data to SD card file "mesh.txt".
|
||||
extern void dcode_81(); //D81 - Bed analysis. This command will log data to SD card file "wldsd.txt".
|
||||
#endif //HEATBED_ANALYSIS
|
||||
|
||||
extern void dcode_106(); //D106 - Print measured fan speed for different pwm values
|
||||
|
||||
#ifdef TMC2130
|
||||
extern void dcode_2130(); //D2130 - TMC2130
|
||||
extern void dcode_2130(); //D2130 - TMC2130
|
||||
#endif //TMC2130
|
||||
|
||||
#ifdef PAT9125
|
||||
extern void dcode_9125(); //D9125 - PAT9125
|
||||
extern void dcode_9125(); //D9125 - PAT9125
|
||||
#endif //PAT9125
|
||||
|
||||
|
||||
|
|
|
|||
|
|
@ -294,7 +294,7 @@ void setPwmFrequency(uint8_t pin, int val);
|
|||
|
||||
extern bool fans_check_enabled;
|
||||
extern float homing_feedrate[];
|
||||
extern bool axis_relative_modes[];
|
||||
extern uint8_t axis_relative_modes;
|
||||
extern float feedrate;
|
||||
extern int feedmultiply;
|
||||
extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
|
||||
|
|
|
|||
|
|
@ -46,6 +46,7 @@
|
|||
//-//
|
||||
#include "Configuration.h"
|
||||
#include "Marlin.h"
|
||||
#include "config.h"
|
||||
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
#include "vector_3.h"
|
||||
|
|
@ -178,9 +179,13 @@ float default_retraction = DEFAULT_RETRACTION;
|
|||
|
||||
|
||||
float homing_feedrate[] = HOMING_FEEDRATE;
|
||||
// Currently only the extruder axis may be switched to a relative mode.
|
||||
// Other axes are always absolute or relative based on the common relative_mode flag.
|
||||
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
|
||||
|
||||
//Although this flag and many others like this could be represented with a struct/bitfield for each axis (more readable and efficient code), the implementation
|
||||
//would not be standard across all platforms. That being said, the code will continue to use bitmasks for independent axis.
|
||||
//Moreover, according to C/C++ standard, the ordering of bits is platform/compiler dependent and the compiler is allowed to align the bits arbitrarily,
|
||||
//thus bit operations like shifting and masking may stop working and will be very hard to fix.
|
||||
uint8_t axis_relative_modes = 0;
|
||||
|
||||
int feedmultiply=100; //100->1 200->2
|
||||
int extrudemultiply=100; //100->1 200->2
|
||||
int extruder_multiply[EXTRUDERS] = {100
|
||||
|
|
@ -710,6 +715,12 @@ static void factory_reset(char level)
|
|||
|
||||
eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
|
||||
eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
|
||||
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_X, 0);
|
||||
eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_Y, 0);
|
||||
eeprom_update_byte((uint8_t *)EEPROM_FERROR_COUNT, 0);
|
||||
eeprom_update_byte((uint8_t *)EEPROM_POWER_COUNT, 0);
|
||||
|
||||
eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_X_TOT, 0);
|
||||
eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_Y_TOT, 0);
|
||||
eeprom_update_word((uint16_t *)EEPROM_FERROR_COUNT_TOT, 0);
|
||||
|
|
@ -1891,10 +1902,6 @@ static void axis_is_at_home(int axis) {
|
|||
max_pos[axis] = base_max_pos(axis) + cs.add_homing[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)); }
|
||||
|
||||
//! @return original feedmultiply
|
||||
static int setup_for_endstop_move(bool enable_endstops_now = true) {
|
||||
saved_feedrate = feedrate;
|
||||
|
|
@ -2189,6 +2196,21 @@ bool calibrate_z_auto()
|
|||
}
|
||||
#endif //TMC2130
|
||||
|
||||
#ifdef TMC2130
|
||||
static void check_Z_crash(void)
|
||||
{
|
||||
if (READ(Z_TMC2130_DIAG) != 0) { //Z crash
|
||||
FORCE_HIGH_POWER_END;
|
||||
current_position[Z_AXIS] = 0;
|
||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||
current_position[Z_AXIS] += MESH_HOME_Z_SEARCH;
|
||||
plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder);
|
||||
st_synchronize();
|
||||
kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
|
||||
}
|
||||
}
|
||||
#endif //TMC2130
|
||||
|
||||
#ifdef TMC2130
|
||||
void homeaxis(int axis, uint8_t cnt, uint8_t* pstep)
|
||||
#else
|
||||
|
|
@ -2305,11 +2327,7 @@ void homeaxis(int axis, uint8_t cnt)
|
|||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||
st_synchronize();
|
||||
#ifdef TMC2130
|
||||
if (READ(Z_TMC2130_DIAG) != 0) { //Z crash
|
||||
FORCE_HIGH_POWER_END;
|
||||
kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
|
||||
return;
|
||||
}
|
||||
check_Z_crash();
|
||||
#endif //TMC2130
|
||||
current_position[axis] = 0;
|
||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||
|
|
@ -2321,11 +2339,7 @@ void homeaxis(int axis, uint8_t cnt)
|
|||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||
st_synchronize();
|
||||
#ifdef TMC2130
|
||||
if (READ(Z_TMC2130_DIAG) != 0) { //Z crash
|
||||
FORCE_HIGH_POWER_END;
|
||||
kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
|
||||
return;
|
||||
}
|
||||
check_Z_crash();
|
||||
#endif //TMC2130
|
||||
axis_is_at_home(axis);
|
||||
destination[axis] = current_position[axis];
|
||||
|
|
@ -5374,21 +5388,19 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
|
|||
|
||||
/*!
|
||||
### G90 - Switch off relative mode <a href="https://reprap.org/wiki/G-code#G90:_Set_to_Absolute_Positioning">G90: Set to Absolute Positioning</a>
|
||||
All coordinates from now on are absolute relative to the origin of the machine. E axis is also switched to absolute mode.
|
||||
All coordinates from now on are absolute relative to the origin of the machine. E axis is left intact.
|
||||
*/
|
||||
case 90: {
|
||||
for(uint8_t i = 0; i != NUM_AXIS; ++i)
|
||||
axis_relative_modes[i] = false;
|
||||
axis_relative_modes &= ~(X_AXIS_MASK | Y_AXIS_MASK | Z_AXIS_MASK);
|
||||
}
|
||||
break;
|
||||
|
||||
/*!
|
||||
### G91 - Switch on relative mode <a href="https://reprap.org/wiki/G-code#G91:_Set_to_Relative_Positioning">G91: Set to Relative Positioning</a>
|
||||
All coordinates from now on are relative to the last position. E axis is also switched to relative mode.
|
||||
All coordinates from now on are relative to the last position. E axis is left intact.
|
||||
*/
|
||||
case 91: {
|
||||
for(uint8_t i = 0; i != NUM_AXIS; ++i)
|
||||
axis_relative_modes[i] = true;
|
||||
axis_relative_modes |= X_AXIS_MASK | Y_AXIS_MASK | Z_AXIS_MASK;
|
||||
}
|
||||
break;
|
||||
|
||||
|
|
@ -6565,7 +6577,7 @@ Sigma_Exit:
|
|||
Makes the extruder interpret extrusion as absolute positions.
|
||||
*/
|
||||
case 82:
|
||||
axis_relative_modes[E_AXIS] = false;
|
||||
axis_relative_modes &= ~E_AXIS_MASK;
|
||||
break;
|
||||
|
||||
/*!
|
||||
|
|
@ -6573,7 +6585,7 @@ Sigma_Exit:
|
|||
Makes the extruder interpret extrusion values as relative positions.
|
||||
*/
|
||||
case 83:
|
||||
axis_relative_modes[E_AXIS] = true;
|
||||
axis_relative_modes |= E_AXIS_MASK;
|
||||
break;
|
||||
|
||||
/*!
|
||||
|
|
@ -7104,7 +7116,6 @@ Sigma_Exit:
|
|||
{
|
||||
float e = code_value();
|
||||
#ifndef LA_NOCOMPAT
|
||||
|
||||
e = la10c_jerk(e);
|
||||
#endif
|
||||
cs.max_jerk[E_AXIS] = e;
|
||||
|
|
@ -8825,7 +8836,7 @@ Sigma_Exit:
|
|||
case 2:
|
||||
dcode_2(); break;
|
||||
#endif //DEBUG_DCODES
|
||||
#ifdef DEBUG_DCODE3
|
||||
#if defined DEBUG_DCODE3 || defined DEBUG_DCODES
|
||||
|
||||
/*!
|
||||
### D3 - Read/Write EEPROM <a href="https://reprap.org/wiki/G-code#D3:_Read.2FWrite_EEPROM">D3: Read/Write EEPROM</a>
|
||||
|
|
@ -8866,7 +8877,7 @@ Sigma_Exit:
|
|||
case 4:
|
||||
dcode_4(); break;
|
||||
#endif //DEBUG_DCODES
|
||||
#ifdef DEBUG_DCODE5
|
||||
#if defined DEBUG_DCODE5 || defined DEBUG_DCODES
|
||||
|
||||
/*!
|
||||
### D5 - Read/Write FLASH <a href="https://reprap.org/wiki/G-code#D5:_Read.2FWrite_FLASH">D5: Read/Write Flash</a>
|
||||
|
|
@ -8878,7 +8889,7 @@ Sigma_Exit:
|
|||
#### Parameters
|
||||
- `A` - Address (x00000-x3ffff)
|
||||
- `C` - Count (1-8192)
|
||||
- `X` - Data
|
||||
- `X` - Data (hex)
|
||||
- `E` - Erase
|
||||
|
||||
#### Notes
|
||||
|
|
@ -8889,7 +8900,6 @@ Sigma_Exit:
|
|||
*/
|
||||
case 5:
|
||||
dcode_5(); break;
|
||||
break;
|
||||
#endif //DEBUG_DCODE5
|
||||
#ifdef DEBUG_DCODES
|
||||
|
||||
|
|
@ -8972,28 +8982,7 @@ Sigma_Exit:
|
|||
- `J` - Offset Y (default 34)
|
||||
*/
|
||||
case 80:
|
||||
{
|
||||
float dimension_x = 40;
|
||||
float dimension_y = 40;
|
||||
int points_x = 40;
|
||||
int points_y = 40;
|
||||
float offset_x = 74;
|
||||
float offset_y = 33;
|
||||
|
||||
if (code_seen('E')) dimension_x = code_value();
|
||||
if (code_seen('F')) dimension_y = code_value();
|
||||
if (code_seen('G')) {points_x = code_value(); }
|
||||
if (code_seen('H')) {points_y = code_value(); }
|
||||
if (code_seen('I')) {offset_x = code_value(); }
|
||||
if (code_seen('J')) {offset_y = code_value(); }
|
||||
printf_P(PSTR("DIM X: %f\n"), dimension_x);
|
||||
printf_P(PSTR("DIM Y: %f\n"), dimension_y);
|
||||
printf_P(PSTR("POINTS X: %d\n"), points_x);
|
||||
printf_P(PSTR("POINTS Y: %d\n"), points_y);
|
||||
printf_P(PSTR("OFFSET X: %f\n"), offset_x);
|
||||
printf_P(PSTR("OFFSET Y: %f\n"), offset_y);
|
||||
bed_check(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
|
||||
}break;
|
||||
dcode_80(); break;
|
||||
|
||||
/*!
|
||||
### D81 - Bed analysis <a href="https://reprap.org/wiki/G-code#D81:_Bed_analysis">D80: Bed analysis</a>
|
||||
|
|
@ -9011,24 +9000,7 @@ Sigma_Exit:
|
|||
- `J` - Offset Y (default 34)
|
||||
*/
|
||||
case 81:
|
||||
{
|
||||
float dimension_x = 40;
|
||||
float dimension_y = 40;
|
||||
int points_x = 40;
|
||||
int points_y = 40;
|
||||
float offset_x = 74;
|
||||
float offset_y = 33;
|
||||
|
||||
if (code_seen('E')) dimension_x = code_value();
|
||||
if (code_seen('F')) dimension_y = code_value();
|
||||
if (code_seen("G")) { strchr_pointer+=1; points_x = code_value(); }
|
||||
if (code_seen("H")) { strchr_pointer+=1; points_y = code_value(); }
|
||||
if (code_seen("I")) { strchr_pointer+=1; offset_x = code_value(); }
|
||||
if (code_seen("J")) { strchr_pointer+=1; offset_y = code_value(); }
|
||||
|
||||
bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
|
||||
|
||||
} break;
|
||||
dcode_81(); break;
|
||||
|
||||
#endif //HEATBED_ANALYSIS
|
||||
#ifdef DEBUG_DCODES
|
||||
|
|
@ -9037,17 +9009,7 @@ Sigma_Exit:
|
|||
### D106 - Print measured fan speed for different pwm values <a href="https://reprap.org/wiki/G-code#D106:_Print_measured_fan_speed_for_different_pwm_values">D106: Print measured fan speed for different pwm values</a>
|
||||
*/
|
||||
case 106:
|
||||
{
|
||||
for (int i = 255; i > 0; i = i - 5) {
|
||||
fanSpeed = i;
|
||||
//delay_keep_alive(2000);
|
||||
for (int j = 0; j < 100; j++) {
|
||||
delay_keep_alive(100);
|
||||
|
||||
}
|
||||
printf_P(_N("%d: %d\n"), i, fan_speed[1]);
|
||||
}
|
||||
}break;
|
||||
dcode_106(); break;
|
||||
|
||||
#ifdef TMC2130
|
||||
/*!
|
||||
|
|
@ -9214,7 +9176,7 @@ void get_coordinates()
|
|||
for(int8_t i=0; i < NUM_AXIS; i++) {
|
||||
if(code_seen(axis_codes[i]))
|
||||
{
|
||||
bool relative = axis_relative_modes[i];
|
||||
bool relative = axis_relative_modes & (1 << i);
|
||||
destination[i] = (float)code_value();
|
||||
if (i == E_AXIS) {
|
||||
float emult = extruder_multiplier[active_extruder];
|
||||
|
|
@ -9484,10 +9446,15 @@ static void handleSafetyTimer()
|
|||
}
|
||||
#endif //SAFETYTIMER
|
||||
|
||||
#define FS_CHECK_COUNT 15
|
||||
void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h
|
||||
{
|
||||
bool bInhibitFlag;
|
||||
#ifdef FILAMENT_SENSOR
|
||||
bool bInhibitFlag;
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
static uint8_t nFSCheckCount=0;
|
||||
#endif // IR_SENSOR_ANALOG
|
||||
|
||||
if (mmu_enabled == false)
|
||||
{
|
||||
//-// if (mcode_in_progress != 600) //M600 not in progress
|
||||
|
|
@ -9496,11 +9463,35 @@ bool bInhibitFlag;
|
|||
#endif // PAT9125
|
||||
#ifdef IR_SENSOR
|
||||
bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
bInhibitFlag=bInhibitFlag||bMenuFSDetect; // Settings::HWsetup::FSdetect menu active
|
||||
#endif // IR_SENSOR_ANALOG
|
||||
#endif // IR_SENSOR
|
||||
if ((mcode_in_progress != 600) && (eFilamentAction != FilamentAction::AutoLoad) && (!bInhibitFlag)) //M600 not in progress, preHeat @ autoLoad menu not active, Support::ExtruderInfo/SensorInfo menu not active
|
||||
{
|
||||
if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE))
|
||||
{
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
bool bTemp=current_voltage_raw_IR>IRsensor_Hmin_TRESHOLD;
|
||||
bTemp=bTemp&¤t_voltage_raw_IR<IRsensor_Hopen_TRESHOLD;
|
||||
bTemp=bTemp&&(!CHECK_ALL_HEATERS);
|
||||
bTemp=bTemp&&(menu_menu==lcd_status_screen);
|
||||
bTemp=bTemp&&((oFsensorPCB==ClFsensorPCB::_Old)||(oFsensorPCB==ClFsensorPCB::_Undef));
|
||||
bTemp=bTemp&&fsensor_enabled;
|
||||
if(bTemp)
|
||||
{
|
||||
nFSCheckCount++;
|
||||
if(nFSCheckCount>FS_CHECK_COUNT)
|
||||
{
|
||||
nFSCheckCount=0; // not necessary
|
||||
oFsensorPCB=ClFsensorPCB::_Rev03b;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB);
|
||||
printf_IRSensorAnalogBoardChange(true);
|
||||
lcd_setstatuspgm(_i("FS rev. 03b or newer"));
|
||||
}
|
||||
}
|
||||
else nFSCheckCount=0;
|
||||
#endif // IR_SENSOR_ANALOG
|
||||
if (fsensor_check_autoload())
|
||||
{
|
||||
#ifdef PAT9125
|
||||
|
|
@ -10613,7 +10604,7 @@ void uvlo_()
|
|||
|
||||
// Store the print E position before we lose track
|
||||
eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), current_position[E_AXIS]);
|
||||
eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, axis_relative_modes[3]?0:1);
|
||||
eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, (axis_relative_modes & E_AXIS_MASK)?0:1);
|
||||
|
||||
// Clean the input command queue, inhibit serial processing using saved_printing
|
||||
cmdqueue_reset();
|
||||
|
|
@ -11202,7 +11193,7 @@ void stop_and_save_print_to_ram(float z_move, float e_move)
|
|||
saved_feedmultiply2 = feedmultiply; //save feedmultiply
|
||||
saved_active_extruder = active_extruder; //save active_extruder
|
||||
saved_extruder_temperature = degTargetHotend(active_extruder);
|
||||
saved_extruder_relative_mode = axis_relative_modes[E_AXIS];
|
||||
saved_extruder_relative_mode = axis_relative_modes & E_AXIS_MASK;
|
||||
saved_fanSpeed = fanSpeed;
|
||||
cmdqueue_reset(); //empty cmdqueue
|
||||
card.sdprinting = false;
|
||||
|
|
@ -11284,7 +11275,7 @@ void restore_print_from_ram_and_continue(float e_move)
|
|||
wait_for_heater(_millis(), saved_active_extruder);
|
||||
heating_status = 2;
|
||||
}
|
||||
axis_relative_modes[E_AXIS] = saved_extruder_relative_mode;
|
||||
axis_relative_modes ^= (-saved_extruder_relative_mode ^ axis_relative_modes) & E_AXIS_MASK;
|
||||
float e = saved_pos[E_AXIS] - e_move;
|
||||
plan_set_e_position(e);
|
||||
|
||||
|
|
|
|||
|
|
@ -5,10 +5,12 @@
|
|||
#include "Configuration_prusa.h"
|
||||
#include "pins.h"
|
||||
|
||||
#define IR_SENSOR_ANALOG (defined(VOLT_IR_PIN) && defined(IR_SENSOR))
|
||||
#if (defined(VOLT_IR_PIN) && defined(IR_SENSOR))
|
||||
# define IR_SENSOR_ANALOG
|
||||
#endif
|
||||
|
||||
//ADC configuration
|
||||
#if !IR_SENSOR_ANALOG
|
||||
#ifndef IR_SENSOR_ANALOG
|
||||
#define ADC_CHAN_MSK 0b0000001001011111 //used AD channels bit mask (0,1,2,3,4,6,9)
|
||||
#define ADC_DIDR_MSK 0b0000001001011111 //AD channels DIDR mask (1 ~ disabled digital input)
|
||||
#define ADC_CHAN_CNT 7 //number of used channels)
|
||||
|
|
@ -56,7 +58,7 @@
|
|||
#define W25X20CL_SPSR SPI_SPSR(W25X20CL_SPI_RATE)
|
||||
|
||||
//LANG - Multi-language support
|
||||
//define LANG_MODE 0 // primary language only
|
||||
//#define LANG_MODE 0 // primary language only
|
||||
#define LANG_MODE 1 // sec. language support
|
||||
|
||||
#define LANG_SIZE_RESERVED 0x3000 // reserved space for secondary language (12288 bytes)
|
||||
|
|
|
|||
|
|
@ -72,7 +72,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
|||
|
||||
To convert hex to dec https://www.rapidtables.com/convert/number/hex-to-decimal.html
|
||||
|
||||
Version: 1.0
|
||||
Version: 1.0.1
|
||||
|
||||
---------------------------------------------------------------------------------
|
||||
|
||||
|
|
@ -225,10 +225,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
|||
| ^ | ^ | ^ | fa 00h 250 | ^ | PRINTER_MK2.5 | ??? | ^
|
||||
| ^ | ^ | ^ | 1a 4fh 20250 | ^ | PRINTER_MK2.5 with MMU2 | ??? | ^
|
||||
| ^ | ^ | ^ | fc 00h 252 | ^ | PRINTER_MK2.5S | ??? | ^
|
||||
| ^ | ^ | ^ | 1c 4fh 20250 | ^ | PRINTER_MK2.5S with MMU2S | ??? | ^
|
||||
| ^ | ^ | ^ | 0c 12h 300 | ^ | PRINTER_MK3 | ??? | ^
|
||||
| ^ | ^ | ^ | 1c 4fh 20252 | ^ | PRINTER_MK2.5S with MMU2S | ??? | ^
|
||||
| ^ | ^ | ^ | 2c 01h 300 | ^ | PRINTER_MK3 | ??? | ^
|
||||
| ^ | ^ | ^ | 4c 4fh 20300 | ^ | PRINTER_MK3 with MMU2 | ??? | ^
|
||||
| ^ | ^ | ^ | 0e 12h 302 | ^ | PRINTER_MK3S | ??? | ^
|
||||
| ^ | ^ | ^ | 2e 01h 302 | ^ | PRINTER_MK3S | ??? | ^
|
||||
| ^ | ^ | ^ | 4e 4fh 20302 | ^ | PRINTER_MK3S with MMU2S | ??? | ^
|
||||
| 0x0EEC 3820 | uint16 | EEPROM_BOARD_TYPE | ??? | ff ffh 65535 | Board Type | ??? | D3 Ax0eec C2
|
||||
| ^ | ^ | ^ | c8 00h 200 | ^ | BOARD_RAMBO_MINI_1_0 | ??? | ^
|
||||
|
|
@ -355,7 +355,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
|||
| 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: __Auto__ | LCD menu | D3 Ax0d32 C1
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: __Bright__ | ^ | ^
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: __Dim__ | ^ | ^
|
||||
| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | ff ffh 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2
|
||||
| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | 0a 00h 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2
|
||||
| 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4
|
||||
|
||||
|
||||
|
|
|
|||
|
|
@ -69,8 +69,10 @@ unsigned long fsensor_softfail_last = 0;
|
|||
uint8_t fsensor_softfail_ccnt = 0;
|
||||
#endif
|
||||
|
||||
#ifdef DEBUG_FSENSOR_LOG
|
||||
//! log flag: 0=log disabled, 1=log enabled
|
||||
uint8_t fsensor_log = 1;
|
||||
#endif //DEBUG_FSENSOR_LOG
|
||||
|
||||
|
||||
//! @name filament autoload variables
|
||||
|
|
@ -119,7 +121,7 @@ int16_t fsensor_oq_yd_max;
|
|||
uint16_t fsensor_oq_sh_sum;
|
||||
//! @}
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
ClFsensorPCB oFsensorPCB;
|
||||
ClFsensorActionNA oFsensorActionNA;
|
||||
bool bIRsensorStateFlag=false;
|
||||
|
|
@ -188,7 +190,7 @@ void fsensor_init(void)
|
|||
fsensor_not_responding = true;
|
||||
}
|
||||
#endif //PAT9125
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
bIRsensorStateFlag=false;
|
||||
oFsensorPCB=(ClFsensorPCB)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_PCB);
|
||||
oFsensorActionNA=(ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA);
|
||||
|
|
@ -198,7 +200,7 @@ void fsensor_init(void)
|
|||
else
|
||||
fsensor_disable(false); // (in this case) EEPROM update is not necessary
|
||||
printf_P(PSTR("FSensor %S"), (fsensor_enabled?PSTR("ENABLED"):PSTR("DISABLED")));
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
printf_P(PSTR(" (sensor board revision: %S)\n"),(oFsensorPCB==ClFsensorPCB::_Rev03b)?PSTR("03b or newer"):PSTR("03 or older"));
|
||||
#else //IR_SENSOR_ANALOG
|
||||
printf_P(PSTR("\n"));
|
||||
|
|
@ -231,7 +233,7 @@ bool fsensor_enable(bool bUpdateEEPROM)
|
|||
FSensorStateMenu = 1;
|
||||
}
|
||||
#else // PAT9125
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
if(!fsensor_IR_check())
|
||||
{
|
||||
bUpdateEEPROM=true;
|
||||
|
|
@ -244,7 +246,7 @@ bool fsensor_enable(bool bUpdateEEPROM)
|
|||
fsensor_enabled=true;
|
||||
fsensor_not_responding=false;
|
||||
FSensorStateMenu=1;
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
}
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
if(bUpdateEEPROM)
|
||||
|
|
@ -660,7 +662,7 @@ void fsensor_update(void)
|
|||
{
|
||||
if(digitalRead(IR_SENSOR_PIN))
|
||||
{ // IR_SENSOR_PIN ~ H
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
if(!bIRsensorStateFlag)
|
||||
{
|
||||
bIRsensorStateFlag=true;
|
||||
|
|
@ -703,7 +705,7 @@ void fsensor_update(void)
|
|||
#endif //IR_SENSOR_ANALOG
|
||||
fsensor_checkpoint_print();
|
||||
fsensor_enque_M600();
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -717,7 +719,7 @@ void fsensor_update(void)
|
|||
#endif //PAT9125
|
||||
}
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
bool fsensor_IR_check()
|
||||
{
|
||||
uint16_t volt_IR_int;
|
||||
|
|
|
|||
|
|
@ -72,6 +72,9 @@ extern bool fsensor_oq_result(void);
|
|||
//! @{
|
||||
extern void fsensor_st_block_chunk(int cnt);
|
||||
|
||||
// debugging
|
||||
extern uint8_t fsensor_log;
|
||||
|
||||
// There's really nothing to do in block_begin: the stepper ISR likely has
|
||||
// called us already at the end of the last block, making this integration
|
||||
// redundant. LA1.5 might not always do that during a coasting move, so attempt
|
||||
|
|
@ -81,7 +84,7 @@ extern void fsensor_st_block_chunk(int cnt);
|
|||
#endif //PAT9125
|
||||
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
#define IR_SENSOR_STEADY 10 // [ms]
|
||||
|
||||
enum class ClFsensorPCB:uint_least8_t
|
||||
|
|
|
|||
|
|
@ -1,190 +1,190 @@
|
|||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include "io_atmega2560.h"
|
||||
|
||||
// All this is about silencing the heat bed, as it behaves like a loudspeaker.
|
||||
// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced
|
||||
// frequency for both power supply units (i.e. both PSUs are reasonably silent).
|
||||
// The only trouble is the rising or falling edge of bed heating - that creates an audible click.
|
||||
// This audible click may be suppressed by making the rising or falling edge NOT sharp.
|
||||
// Of course, making non-sharp edges in digital technology is not easy, but there is a solution.
|
||||
// It is possible to do a fast PWM sequence with duty starting from 0 to 255.
|
||||
// Doing this at higher frequency than the bed "loudspeaker" can handle makes the click barely audible.
|
||||
// Technically:
|
||||
// timer0 is set to fast PWM mode at 62.5kHz (timer0 is linked to the bed heating pin) (zero prescaler)
|
||||
// To keep the bed switching at 30Hz - we don't want the PWM running at 62kHz all the time
|
||||
// since it would burn the heatbed's MOSFET:
|
||||
// 16MHz/256 levels of PWM duty gives us 62.5kHz
|
||||
// 62.5kHz/256 gives ~244Hz, that is still too fast - 244/8 gives ~30Hz, that's what we need
|
||||
// So the automaton runs atop of inner 8 (or 16) cycles.
|
||||
// The finite automaton is running in the ISR(TIMER0_OVF_vect)
|
||||
|
||||
// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions:
|
||||
// 1. 62kHz ISR requires considerable amount of processing power,
|
||||
// USB transfer speed dropped by 20%, which was most notable when doing short G-code segments.
|
||||
// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz.
|
||||
// This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz
|
||||
// To address both issues, there is an improved approach based on the idea of leveraging
|
||||
// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin,
|
||||
// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64).
|
||||
// That shall result in the ISR not being called that much resulting in regained performance
|
||||
// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer
|
||||
// control registers correctly, especially setting them in a correct order.
|
||||
// Some registers are double buffered, some changes are applied in next cycles etc.
|
||||
// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers,
|
||||
// we don't want to reset the prescaler counted value when transiting among automaton states.
|
||||
// Resetting the prescaler would make the PWM more precise, right now there are temporal segments
|
||||
// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync"
|
||||
// to the new slower CLK after setting the slower prescaler value.
|
||||
// In our application, this isn't any significant problem and may be ignored.
|
||||
// Doing changes in timer's registers non-correctly results in artefacts on the output pin
|
||||
// - it can toggle unnoticed, which will result in bed clicking again.
|
||||
// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the
|
||||
// counter change its operation atomically and without artefacts on the output pin.
|
||||
// The resulting signal on the output pin was checked with an osciloscope.
|
||||
// If there are any change requirements in the future, the signal must be checked with an osciloscope again,
|
||||
// ad-hoc changes may completely screw things up!
|
||||
|
||||
// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state
|
||||
// to either full ON or OFF. This is so that interference during the MBL probing is minimal.
|
||||
// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to
|
||||
// not make the bed temperature too unstable. Also, careful consideration should be used when using this
|
||||
// option as leaving this enabled will also keep the bed output in the state it stopped in.
|
||||
|
||||
///! Definition off finite automaton states
|
||||
enum class States : uint8_t {
|
||||
ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle
|
||||
ZERO, ///< steady 0 (OFF), no change for the whole period
|
||||
ZERO_TO_RISE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
RISE, ///< 16 fast PWM cycles with increasing duty up to steady ON
|
||||
RISE_TO_ONE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
ONE, ///< steady 1 (ON), no change for the whole period
|
||||
ONE_TO_FALL, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
FALL, ///< 16 fast PWM cycles with decreasing duty down to steady OFF
|
||||
FALL_TO_ZERO ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
};
|
||||
|
||||
///! Inner states of the finite automaton
|
||||
static States state = States::ZERO_START;
|
||||
|
||||
bool bedPWMDisabled = 0;
|
||||
|
||||
///! Fast PWM counter is used in the RISE and FALL states (62.5kHz)
|
||||
static uint8_t slowCounter = 0;
|
||||
///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64)
|
||||
static uint8_t fastCounter = 0;
|
||||
///! PWM counter for the whole cycle - a cache for soft_pwm_bed
|
||||
static uint8_t pwm = 0;
|
||||
|
||||
///! The slow PWM duty for the next 30Hz cycle
|
||||
///! Set in the whole firmware at various places
|
||||
extern unsigned char soft_pwm_bed;
|
||||
|
||||
/// fastMax - how many fast PWM steps to do in RISE and FALL states
|
||||
/// 16 is a good compromise between silenced bed ("smooth" edges)
|
||||
/// and not burning the switching MOSFET
|
||||
static const uint8_t fastMax = 16;
|
||||
|
||||
/// Scaler 16->256 for fast PWM
|
||||
static const uint8_t fastShift = 4;
|
||||
|
||||
/// Increment slow PWM counter by slowInc every ZERO or ONE state
|
||||
/// This allows for fine-tuning the basic PWM switching frequency
|
||||
/// A possible further optimization - use a 64 prescaler (instead of 8)
|
||||
/// increment slowCounter by 1
|
||||
/// but use less bits of soft PWM - something like soft_pwm_bed >> 2
|
||||
/// that may further reduce the CPU cycles required by the bed heating automaton
|
||||
/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance
|
||||
static const uint8_t slowInc = 1;
|
||||
|
||||
ISR(TIMER0_OVF_vect) // timer compare interrupt service routine
|
||||
{
|
||||
switch(state){
|
||||
case States::ZERO_START:
|
||||
if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin
|
||||
pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit!
|
||||
if( pwm != 0 ){
|
||||
state = States::ZERO; // do nothing, let it tick once again after the 30Hz period
|
||||
}
|
||||
break;
|
||||
case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE
|
||||
// In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed
|
||||
slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc)
|
||||
if( slowCounter > pwm ){
|
||||
return;
|
||||
} // otherwise moving towards RISE
|
||||
state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0
|
||||
break;
|
||||
// even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it
|
||||
// the timer must tick once more in order to get rid of occasional output pin toggles.
|
||||
case States::ZERO_TO_RISE: // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin.
|
||||
// It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle.
|
||||
// Also beware of the correct sequence of the following timer control registers initialization - it really matters!
|
||||
state = States::RISE; // prepare for standard RISE cycles
|
||||
fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
|
||||
TCNT0 = 255; // force overflow on the next clock cycle
|
||||
TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode)
|
||||
break;
|
||||
case States::RISE:
|
||||
OCR0B = (fastMax - fastCounter) << fastShift;
|
||||
if( fastCounter ){
|
||||
--fastCounter;
|
||||
} else { // end of RISE cycles, changing into state ONE
|
||||
state = States::RISE_TO_ONE;
|
||||
OCR0B = 255; // full duty
|
||||
TCNT0 = 254; // make the timer overflow in the next cycle
|
||||
// @@TODO these constants are still subject to investigation
|
||||
}
|
||||
break;
|
||||
case States::RISE_TO_ONE:
|
||||
state = States::ONE;
|
||||
OCR0B = 255; // full duty
|
||||
TCNT0 = 255; // make the timer overflow in the next cycle
|
||||
TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
|
||||
break;
|
||||
case States::ONE: // state ONE - we'll either stay in ONE or change to FALL
|
||||
OCR0B = 255;
|
||||
if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin
|
||||
slowCounter += slowInc; // this does software timer_clk/256 or less
|
||||
if( slowCounter < pwm ){
|
||||
return;
|
||||
}
|
||||
if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain
|
||||
// if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating
|
||||
return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf
|
||||
}
|
||||
// otherwise moving towards FALL
|
||||
// @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all
|
||||
state = States::ONE;//_TO_FALL;
|
||||
// TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
// break;
|
||||
// case States::ONE_TO_FALL:
|
||||
// OCR0B = 255; // zero duty
|
||||
state=States::FALL;
|
||||
fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
|
||||
TCNT0 = 255; // force overflow on the next clock cycle
|
||||
TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
// must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle
|
||||
// COM0B1 remains set both in inverting and non-inverting mode
|
||||
TCCR0A |= (1 << COM0B0); // inverting mode
|
||||
break;
|
||||
case States::FALL:
|
||||
OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode
|
||||
//TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL
|
||||
if( fastCounter ){
|
||||
--fastCounter;
|
||||
} else { // end of FALL cycles, changing into state ZERO
|
||||
state = States::FALL_TO_ZERO;
|
||||
TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes
|
||||
OCR0B = 255;
|
||||
}
|
||||
break;
|
||||
case States::FALL_TO_ZERO:
|
||||
state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle
|
||||
TCNT0 = 128;
|
||||
OCR0B = 255;
|
||||
TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
|
||||
break;
|
||||
}
|
||||
}
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include "io_atmega2560.h"
|
||||
|
||||
// All this is about silencing the heat bed, as it behaves like a loudspeaker.
|
||||
// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced
|
||||
// frequency for both power supply units (i.e. both PSUs are reasonably silent).
|
||||
// The only trouble is the rising or falling edge of bed heating - that creates an audible click.
|
||||
// This audible click may be suppressed by making the rising or falling edge NOT sharp.
|
||||
// Of course, making non-sharp edges in digital technology is not easy, but there is a solution.
|
||||
// It is possible to do a fast PWM sequence with duty starting from 0 to 255.
|
||||
// Doing this at higher frequency than the bed "loudspeaker" can handle makes the click barely audible.
|
||||
// Technically:
|
||||
// timer0 is set to fast PWM mode at 62.5kHz (timer0 is linked to the bed heating pin) (zero prescaler)
|
||||
// To keep the bed switching at 30Hz - we don't want the PWM running at 62kHz all the time
|
||||
// since it would burn the heatbed's MOSFET:
|
||||
// 16MHz/256 levels of PWM duty gives us 62.5kHz
|
||||
// 62.5kHz/256 gives ~244Hz, that is still too fast - 244/8 gives ~30Hz, that's what we need
|
||||
// So the automaton runs atop of inner 8 (or 16) cycles.
|
||||
// The finite automaton is running in the ISR(TIMER0_OVF_vect)
|
||||
|
||||
// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions:
|
||||
// 1. 62kHz ISR requires considerable amount of processing power,
|
||||
// USB transfer speed dropped by 20%, which was most notable when doing short G-code segments.
|
||||
// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz.
|
||||
// This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz
|
||||
// To address both issues, there is an improved approach based on the idea of leveraging
|
||||
// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin,
|
||||
// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64).
|
||||
// That shall result in the ISR not being called that much resulting in regained performance
|
||||
// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer
|
||||
// control registers correctly, especially setting them in a correct order.
|
||||
// Some registers are double buffered, some changes are applied in next cycles etc.
|
||||
// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers,
|
||||
// we don't want to reset the prescaler counted value when transiting among automaton states.
|
||||
// Resetting the prescaler would make the PWM more precise, right now there are temporal segments
|
||||
// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync"
|
||||
// to the new slower CLK after setting the slower prescaler value.
|
||||
// In our application, this isn't any significant problem and may be ignored.
|
||||
// Doing changes in timer's registers non-correctly results in artefacts on the output pin
|
||||
// - it can toggle unnoticed, which will result in bed clicking again.
|
||||
// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the
|
||||
// counter change its operation atomically and without artefacts on the output pin.
|
||||
// The resulting signal on the output pin was checked with an osciloscope.
|
||||
// If there are any change requirements in the future, the signal must be checked with an osciloscope again,
|
||||
// ad-hoc changes may completely screw things up!
|
||||
|
||||
// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state
|
||||
// to either full ON or OFF. This is so that interference during the MBL probing is minimal.
|
||||
// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to
|
||||
// not make the bed temperature too unstable. Also, careful consideration should be used when using this
|
||||
// option as leaving this enabled will also keep the bed output in the state it stopped in.
|
||||
|
||||
///! Definition off finite automaton states
|
||||
enum class States : uint8_t {
|
||||
ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle
|
||||
ZERO, ///< steady 0 (OFF), no change for the whole period
|
||||
ZERO_TO_RISE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
RISE, ///< 16 fast PWM cycles with increasing duty up to steady ON
|
||||
RISE_TO_ONE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
ONE, ///< steady 1 (ON), no change for the whole period
|
||||
ONE_TO_FALL, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
FALL, ///< 16 fast PWM cycles with decreasing duty down to steady OFF
|
||||
FALL_TO_ZERO ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
};
|
||||
|
||||
///! Inner states of the finite automaton
|
||||
static States state = States::ZERO_START;
|
||||
|
||||
bool bedPWMDisabled = 0;
|
||||
|
||||
///! Fast PWM counter is used in the RISE and FALL states (62.5kHz)
|
||||
static uint8_t slowCounter = 0;
|
||||
///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64)
|
||||
static uint8_t fastCounter = 0;
|
||||
///! PWM counter for the whole cycle - a cache for soft_pwm_bed
|
||||
static uint8_t pwm = 0;
|
||||
|
||||
///! The slow PWM duty for the next 30Hz cycle
|
||||
///! Set in the whole firmware at various places
|
||||
extern unsigned char soft_pwm_bed;
|
||||
|
||||
/// fastMax - how many fast PWM steps to do in RISE and FALL states
|
||||
/// 16 is a good compromise between silenced bed ("smooth" edges)
|
||||
/// and not burning the switching MOSFET
|
||||
static const uint8_t fastMax = 16;
|
||||
|
||||
/// Scaler 16->256 for fast PWM
|
||||
static const uint8_t fastShift = 4;
|
||||
|
||||
/// Increment slow PWM counter by slowInc every ZERO or ONE state
|
||||
/// This allows for fine-tuning the basic PWM switching frequency
|
||||
/// A possible further optimization - use a 64 prescaler (instead of 8)
|
||||
/// increment slowCounter by 1
|
||||
/// but use less bits of soft PWM - something like soft_pwm_bed >> 2
|
||||
/// that may further reduce the CPU cycles required by the bed heating automaton
|
||||
/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance
|
||||
static const uint8_t slowInc = 1;
|
||||
|
||||
ISR(TIMER0_OVF_vect) // timer compare interrupt service routine
|
||||
{
|
||||
switch(state){
|
||||
case States::ZERO_START:
|
||||
if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin
|
||||
pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit!
|
||||
if( pwm != 0 ){
|
||||
state = States::ZERO; // do nothing, let it tick once again after the 30Hz period
|
||||
}
|
||||
break;
|
||||
case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE
|
||||
// In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed
|
||||
slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc)
|
||||
if( slowCounter > pwm ){
|
||||
return;
|
||||
} // otherwise moving towards RISE
|
||||
state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0
|
||||
break;
|
||||
// even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it
|
||||
// the timer must tick once more in order to get rid of occasional output pin toggles.
|
||||
case States::ZERO_TO_RISE: // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin.
|
||||
// It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle.
|
||||
// Also beware of the correct sequence of the following timer control registers initialization - it really matters!
|
||||
state = States::RISE; // prepare for standard RISE cycles
|
||||
fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
|
||||
TCNT0 = 255; // force overflow on the next clock cycle
|
||||
TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode)
|
||||
break;
|
||||
case States::RISE:
|
||||
OCR0B = (fastMax - fastCounter) << fastShift;
|
||||
if( fastCounter ){
|
||||
--fastCounter;
|
||||
} else { // end of RISE cycles, changing into state ONE
|
||||
state = States::RISE_TO_ONE;
|
||||
OCR0B = 255; // full duty
|
||||
TCNT0 = 254; // make the timer overflow in the next cycle
|
||||
// @@TODO these constants are still subject to investigation
|
||||
}
|
||||
break;
|
||||
case States::RISE_TO_ONE:
|
||||
state = States::ONE;
|
||||
OCR0B = 255; // full duty
|
||||
TCNT0 = 255; // make the timer overflow in the next cycle
|
||||
TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
|
||||
break;
|
||||
case States::ONE: // state ONE - we'll either stay in ONE or change to FALL
|
||||
OCR0B = 255;
|
||||
if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin
|
||||
slowCounter += slowInc; // this does software timer_clk/256 or less
|
||||
if( slowCounter < pwm ){
|
||||
return;
|
||||
}
|
||||
if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain
|
||||
// if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating
|
||||
return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf
|
||||
}
|
||||
// otherwise moving towards FALL
|
||||
// @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all
|
||||
state = States::ONE;//_TO_FALL;
|
||||
// TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
// break;
|
||||
// case States::ONE_TO_FALL:
|
||||
// OCR0B = 255; // zero duty
|
||||
state=States::FALL;
|
||||
fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
|
||||
TCNT0 = 255; // force overflow on the next clock cycle
|
||||
TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
// must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle
|
||||
// COM0B1 remains set both in inverting and non-inverting mode
|
||||
TCCR0A |= (1 << COM0B0); // inverting mode
|
||||
break;
|
||||
case States::FALL:
|
||||
OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode
|
||||
//TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL
|
||||
if( fastCounter ){
|
||||
--fastCounter;
|
||||
} else { // end of FALL cycles, changing into state ZERO
|
||||
state = States::FALL_TO_ZERO;
|
||||
TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes
|
||||
OCR0B = 255;
|
||||
}
|
||||
break;
|
||||
case States::FALL_TO_ZERO:
|
||||
state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle
|
||||
TCNT0 = 128;
|
||||
OCR0B = 255;
|
||||
TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -37,7 +37,7 @@ void la10c_mode_change(LA10C_MODE mode)
|
|||
// Approximate a LA10 value to a LA15 equivalent.
|
||||
static float la10c_convert(float k)
|
||||
{
|
||||
float new_K = k * 0.004 - 0.06;
|
||||
float new_K = k * 0.004 - 0.05;
|
||||
return (new_K < 0? 0: new_K);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -383,8 +383,9 @@ void mmu_loop(void)
|
|||
//printf_P(PSTR("Eact: %d\n"), int(e_active()));
|
||||
if (!mmu_finda && CHECK_FSENSOR && fsensor_enabled) {
|
||||
fsensor_checkpoint_print();
|
||||
ad_markDepleted(mmu_extruder);
|
||||
if (lcd_autoDepleteEnabled() && !ad_allDepleted())
|
||||
if (mmu_extruder != MMU_FILAMENT_UNKNOWN) // Can't deplete unknown extruder.
|
||||
ad_markDepleted(mmu_extruder);
|
||||
if (lcd_autoDepleteEnabled() && !ad_allDepleted() && mmu_extruder != MMU_FILAMENT_UNKNOWN) // Can't auto if F=?
|
||||
{
|
||||
enquecommand_front_P(PSTR("M600 AUTO")); //save print and run M600 command
|
||||
}
|
||||
|
|
@ -795,8 +796,8 @@ void mmu_load_to_nozzle()
|
|||
{
|
||||
st_synchronize();
|
||||
|
||||
bool saved_e_relative_mode = axis_relative_modes[E_AXIS];
|
||||
if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = true;
|
||||
const bool saved_e_relative_mode = axis_relative_modes & E_AXIS_MASK;
|
||||
if (!saved_e_relative_mode) axis_relative_modes |= E_AXIS_MASK;
|
||||
if (ir_sensor_detected)
|
||||
{
|
||||
current_position[E_AXIS] += 3.0f;
|
||||
|
|
@ -820,7 +821,7 @@ void mmu_load_to_nozzle()
|
|||
feedrate = 871;
|
||||
plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
|
||||
st_synchronize();
|
||||
if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = false;
|
||||
if (!saved_e_relative_mode) axis_relative_modes &= ~E_AXIS_MASK;
|
||||
}
|
||||
|
||||
void mmu_M600_wait_and_beep() {
|
||||
|
|
|
|||
|
|
@ -1061,16 +1061,16 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
/**
|
||||
* Use LIN_ADVANCE within this block if all these are true:
|
||||
*
|
||||
* block->steps_e : This is a print move, because we checked for X, Y, Z steps before.
|
||||
* extruder_advance_K : There is an advance factor set.
|
||||
* delta_mm[E_AXIS] > 0 : Extruder is running forward (e.g., for "Wipe while retracting" (Slic3r) or "Combing" (Cura) moves)
|
||||
* delta_mm[E_AXIS] >= 0 : Extruding or traveling, but _not_ retracting.
|
||||
* |delta_mm[Z_AXIS]| < 0.5 : Z is only moved for leveling (_not_ for priming)
|
||||
*/
|
||||
block->use_advance_lead = block->steps_e.wide
|
||||
&& extruder_advance_K
|
||||
&& delta_mm[E_AXIS] > 0
|
||||
block->use_advance_lead = extruder_advance_K > 0
|
||||
&& delta_mm[E_AXIS] >= 0
|
||||
&& abs(delta_mm[Z_AXIS]) < 0.5;
|
||||
if (block->use_advance_lead) {
|
||||
// all extrusion moves with LA require a compression which is proportional to the
|
||||
// extrusion_length to distance ratio (e/D)
|
||||
e_D_ratio = (e - position_float[E_AXIS]) /
|
||||
sqrt(sq(x - position_float[X_AXIS])
|
||||
+ sq(y - position_float[Y_AXIS])
|
||||
|
|
@ -1082,10 +1082,10 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
// 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament.
|
||||
if (e_D_ratio > 3.0)
|
||||
block->use_advance_lead = false;
|
||||
else {
|
||||
const uint32_t max_accel_steps_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio) * steps_per_mm;
|
||||
if (block->acceleration_st > max_accel_steps_per_s2) {
|
||||
block->acceleration_st = max_accel_steps_per_s2;
|
||||
else if (e_D_ratio > 0) {
|
||||
const float max_accel_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio);
|
||||
if (cs.acceleration > max_accel_per_s2) {
|
||||
block->acceleration_st = ceil(max_accel_per_s2 * steps_per_mm);
|
||||
#ifdef LA_DEBUG
|
||||
SERIAL_ECHOLNPGM("LA: Block acceleration limited due to max E-jerk");
|
||||
#endif
|
||||
|
|
@ -1133,9 +1133,14 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
block->adv_comp = extruder_advance_K * e_D_ratio * cs.axis_steps_per_unit[E_AXIS];
|
||||
block->max_adv_steps = block->nominal_speed * block->adv_comp;
|
||||
|
||||
float advance_speed;
|
||||
if (e_D_ratio > 0)
|
||||
advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]);
|
||||
else
|
||||
advance_speed = cs.max_jerk[E_AXIS] * cs.axis_steps_per_unit[E_AXIS];
|
||||
|
||||
// to save more space we avoid another copy of calc_timer and go through slow division, but we
|
||||
// still need to replicate the *exact* same step grouping policy (see below)
|
||||
float advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]);
|
||||
if (advance_speed > MAX_STEP_FREQUENCY) advance_speed = MAX_STEP_FREQUENCY;
|
||||
float advance_rate = (F_CPU / 8.0) / advance_speed;
|
||||
if (advance_speed > 20000) {
|
||||
|
|
|
|||
|
|
@ -173,6 +173,9 @@ void plan_set_e_position(const float &e);
|
|||
// Reset the E position to zero at the start of the next segment
|
||||
void plan_reset_next_e();
|
||||
|
||||
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)); }
|
||||
|
||||
extern bool e_active();
|
||||
|
||||
void check_axes_activity();
|
||||
|
|
|
|||
|
|
@ -117,8 +117,8 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
|
|||
void advance_isr();
|
||||
|
||||
static const uint16_t ADV_NEVER = 0xFFFF;
|
||||
static const uint8_t ADV_INIT = 0b01;
|
||||
static const uint8_t ADV_DECELERATE = 0b10;
|
||||
static const uint8_t ADV_INIT = 0b01; // initialize LA
|
||||
static const uint8_t ADV_ACC_VARY = 0b10; // varying acceleration phase
|
||||
|
||||
static uint16_t nextMainISR;
|
||||
static uint16_t nextAdvanceISR;
|
||||
|
|
@ -128,13 +128,12 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
|
|||
static uint16_t eISR_Err;
|
||||
|
||||
static uint16_t current_adv_steps;
|
||||
static uint16_t final_adv_steps;
|
||||
static uint16_t max_adv_steps;
|
||||
static uint32_t LA_decelerate_after;
|
||||
static uint16_t target_adv_steps;
|
||||
|
||||
static int8_t e_steps;
|
||||
static uint8_t e_step_loops;
|
||||
static int8_t LA_phase;
|
||||
static int8_t e_steps; // scheduled e-steps during each isr loop
|
||||
static uint8_t e_step_loops; // e-steps to execute at most in each isr loop
|
||||
static uint8_t e_extruding; // current move is an extrusion move
|
||||
static int8_t LA_phase; // LA compensation phase
|
||||
|
||||
#define _NEXT_ISR(T) main_Rate = nextMainISR = T
|
||||
#else
|
||||
|
|
@ -349,15 +348,12 @@ FORCE_INLINE void stepper_next_block()
|
|||
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
LA_decelerate_after = current_block->decelerate_after;
|
||||
final_adv_steps = current_block->final_adv_steps;
|
||||
max_adv_steps = current_block->max_adv_steps;
|
||||
e_step_loops = current_block->advance_step_loops;
|
||||
target_adv_steps = current_block->max_adv_steps;
|
||||
} else {
|
||||
e_steps = 0;
|
||||
e_step_loops = 1;
|
||||
current_adv_steps = 0;
|
||||
}
|
||||
e_steps = 0;
|
||||
nextAdvanceISR = ADV_NEVER;
|
||||
LA_phase = -1;
|
||||
#endif
|
||||
|
|
@ -371,11 +367,17 @@ FORCE_INLINE void stepper_next_block()
|
|||
counter_y.lo = counter_x.lo;
|
||||
counter_z.lo = counter_x.lo;
|
||||
counter_e.lo = counter_x.lo;
|
||||
#ifdef LIN_ADVANCE
|
||||
e_extruding = current_block->steps_e.lo != 0;
|
||||
#endif
|
||||
} else {
|
||||
counter_x.wide = -(current_block->step_event_count.wide >> 1);
|
||||
counter_y.wide = counter_x.wide;
|
||||
counter_z.wide = counter_x.wide;
|
||||
counter_e.wide = counter_x.wide;
|
||||
#ifdef LIN_ADVANCE
|
||||
e_extruding = current_block->steps_e.wide != 0;
|
||||
#endif
|
||||
}
|
||||
step_events_completed.wide = 0;
|
||||
// Set directions.
|
||||
|
|
@ -811,7 +813,7 @@ FORCE_INLINE void isr() {
|
|||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
if (step_events_completed.wide <= (unsigned long int)step_loops)
|
||||
la_state = ADV_INIT;
|
||||
la_state = ADV_INIT | ADV_ACC_VARY;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
@ -827,11 +829,13 @@ FORCE_INLINE void isr() {
|
|||
uint16_t timer = calc_timer(step_rate, step_loops);
|
||||
_NEXT_ISR(timer);
|
||||
deceleration_time += timer;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
la_state = ADV_DECELERATE;
|
||||
if (step_events_completed.wide <= (unsigned long int)current_block->decelerate_after + step_loops)
|
||||
la_state |= ADV_INIT;
|
||||
if (step_events_completed.wide <= (unsigned long int)current_block->decelerate_after + step_loops) {
|
||||
target_adv_steps = current_block->final_adv_steps;
|
||||
la_state = ADV_INIT | ADV_ACC_VARY;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
@ -841,6 +845,17 @@ FORCE_INLINE void isr() {
|
|||
// the initial interrupt blocking.
|
||||
OCR1A_nominal = calc_timer(uint16_t(current_block->nominal_rate), step_loops);
|
||||
step_loops_nominal = step_loops;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
if(current_block->use_advance_lead) {
|
||||
if (!nextAdvanceISR) {
|
||||
// Due to E-jerk, there can be discontinuities in pressure state where an
|
||||
// acceleration or deceleration can be skipped or joined with the previous block.
|
||||
// If LA was not previously active, re-check the pressure level
|
||||
la_state = ADV_INIT;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
_NEXT_ISR(OCR1A_nominal);
|
||||
}
|
||||
|
|
@ -849,10 +864,23 @@ FORCE_INLINE void isr() {
|
|||
|
||||
#ifdef LIN_ADVANCE
|
||||
// avoid multiple instances or function calls to advance_spread
|
||||
if (la_state & ADV_INIT) eISR_Err = current_block->advance_rate / 4;
|
||||
if (la_state & ADV_INIT) {
|
||||
if (current_adv_steps == target_adv_steps) {
|
||||
// nothing to be done in this phase
|
||||
la_state = 0;
|
||||
}
|
||||
else {
|
||||
eISR_Err = current_block->advance_rate / 4;
|
||||
if ((la_state & ADV_ACC_VARY) && e_extruding && (current_adv_steps > target_adv_steps)) {
|
||||
// LA could reverse the direction of extrusion in this phase
|
||||
LA_phase = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (la_state & ADV_INIT || nextAdvanceISR != ADV_NEVER) {
|
||||
// update timers & phase for the next iteration
|
||||
advance_spread(main_Rate);
|
||||
if (la_state & ADV_DECELERATE) {
|
||||
if (LA_phase >= 0) {
|
||||
if (step_loops == e_step_loops)
|
||||
LA_phase = (eISR_Rate > main_Rate);
|
||||
else {
|
||||
|
|
@ -898,7 +926,7 @@ FORCE_INLINE void isr() {
|
|||
// Timer interrupt for E. e_steps is set in the main routine.
|
||||
|
||||
FORCE_INLINE void advance_isr() {
|
||||
if (step_events_completed.wide > LA_decelerate_after && current_adv_steps > final_adv_steps) {
|
||||
if (current_adv_steps > target_adv_steps) {
|
||||
// decompression
|
||||
e_steps -= e_step_loops;
|
||||
if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR);
|
||||
|
|
@ -908,7 +936,7 @@ FORCE_INLINE void advance_isr() {
|
|||
current_adv_steps = 0;
|
||||
nextAdvanceISR = eISR_Rate;
|
||||
}
|
||||
else if (step_events_completed.wide < LA_decelerate_after && current_adv_steps < max_adv_steps) {
|
||||
else if (current_adv_steps < target_adv_steps) {
|
||||
// compression
|
||||
e_steps += e_step_loops;
|
||||
if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR);
|
||||
|
|
@ -1233,9 +1261,6 @@ void st_init()
|
|||
nextMainISR = 0;
|
||||
nextAdvanceISR = ADV_NEVER;
|
||||
main_Rate = ADV_NEVER;
|
||||
e_steps = 0;
|
||||
e_step_loops = 1;
|
||||
LA_phase = -1;
|
||||
current_adv_steps = 0;
|
||||
#endif
|
||||
|
||||
|
|
|
|||
|
|
@ -73,7 +73,7 @@ int current_voltage_raw_pwr = 0;
|
|||
int current_voltage_raw_bed = 0;
|
||||
#endif
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
int current_voltage_raw_IR = 0;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
|
|
@ -210,6 +210,14 @@ static void temp_runaway_check(int _heater_id, float _target_temperature, float
|
|||
static void temp_runaway_stop(bool isPreheat, bool isBed);
|
||||
#endif
|
||||
|
||||
// return "false", if all extruder-heaters are 'off' (ie. "true", if any heater is 'on')
|
||||
bool checkAllHotends(void)
|
||||
{
|
||||
bool result=false;
|
||||
for(int i=0;i<EXTRUDERS;i++) result=(result||(target_temperature[i]!=0));
|
||||
return(result);
|
||||
}
|
||||
|
||||
void PID_autotune(float temp, int extruder, int ncycles)
|
||||
{
|
||||
pid_number_of_cycles = ncycles;
|
||||
|
|
@ -1588,7 +1596,7 @@ void adc_ready(void) //callback from adc when sampling finished
|
|||
#ifdef VOLT_BED_PIN
|
||||
current_voltage_raw_bed = adc_values[ADC_PIN_IDX(VOLT_BED_PIN)]; // 6->9
|
||||
#endif
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
current_voltage_raw_IR = adc_values[ADC_PIN_IDX(VOLT_IR_PIN)];
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
temp_meas_ready = true;
|
||||
|
|
|
|||
|
|
@ -47,6 +47,8 @@
|
|||
void tp_init(); //initialize the heating
|
||||
void manage_heater(); //it is critical that this is called periodically.
|
||||
|
||||
extern bool checkAllHotends(void);
|
||||
|
||||
// low level conversion routines
|
||||
// do not use these routines and variables outside of temperature.cpp
|
||||
extern int target_temperature[EXTRUDERS];
|
||||
|
|
@ -76,7 +78,7 @@ extern int current_voltage_raw_pwr;
|
|||
extern int current_voltage_raw_bed;
|
||||
#endif
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
extern int current_voltage_raw_IR;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
|
|
@ -222,6 +224,9 @@ FORCE_INLINE bool isCoolingBed() {
|
|||
#error Invalid number of extruders
|
||||
#endif
|
||||
|
||||
// return "false", if all heaters are 'off' (ie. "true", if any heater is 'on')
|
||||
#define CHECK_ALL_HEATERS (checkAllHotends()||(target_temperature_bed!=0))
|
||||
|
||||
int getHeaterPower(int heater);
|
||||
void disable_heater();
|
||||
void updatePID();
|
||||
|
|
|
|||
|
|
@ -64,6 +64,10 @@ uint8_t SilentModeMenu_MMU = 1; //activate mmu unit stealth mode
|
|||
|
||||
int8_t FSensorStateMenu = 1;
|
||||
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
bool bMenuFSDetect=false;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
|
||||
#ifdef SDCARD_SORT_ALPHA
|
||||
bool presort_flag = false;
|
||||
|
|
@ -110,7 +114,7 @@ static const char* lcd_display_message_fullscreen_nonBlocking_P(const char *msg,
|
|||
// void copy_and_scalePID_d();
|
||||
|
||||
/* Different menus */
|
||||
static void lcd_status_screen();
|
||||
//static void lcd_status_screen(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
#if (LANG_MODE != 0)
|
||||
static void lcd_language_menu();
|
||||
#endif
|
||||
|
|
@ -160,10 +164,10 @@ static void reset_crash_det(unsigned char axis);
|
|||
static bool lcd_selfcheck_axis_sg(unsigned char axis);
|
||||
static bool lcd_selfcheck_axis(int _axis, int _travel);
|
||||
#else
|
||||
static bool lcd_selfcheck_endstops();
|
||||
static bool lcd_selfcheck_axis(int _axis, int _travel);
|
||||
static bool lcd_selfcheck_pulleys(int axis);
|
||||
#endif //TMC2130
|
||||
static bool lcd_selfcheck_endstops();
|
||||
|
||||
static bool lcd_selfcheck_check_heater(bool _isbed);
|
||||
enum class TestScreen : uint_least8_t
|
||||
|
|
@ -231,8 +235,9 @@ static FanCheck lcd_selftest_fan_auto(int _fan);
|
|||
static bool lcd_selftest_fsensor();
|
||||
#endif //PAT9125
|
||||
static bool selftest_irsensor();
|
||||
#if IR_SENSOR_ANALOG
|
||||
static bool lcd_selftest_IRsensor();
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
static bool lcd_selftest_IRsensor(bool bStandalone=false);
|
||||
static void lcd_detect_IRsensor();
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
static void lcd_selftest_error(TestError error, const char *_error_1, const char *_error_2);
|
||||
static void lcd_colorprint_change();
|
||||
|
|
@ -792,7 +797,7 @@ void lcdui_print_status_screen(void)
|
|||
}
|
||||
|
||||
// Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependent
|
||||
static void lcd_status_screen()
|
||||
void lcd_status_screen() // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
{
|
||||
if (firstrun == 1)
|
||||
{
|
||||
|
|
@ -1769,7 +1774,7 @@ static void lcd_menu_temperatures()
|
|||
menu_back_if_clicked();
|
||||
}
|
||||
|
||||
#if defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || IR_SENSOR_ANALOG
|
||||
#if defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || defined(IR_SENSOR_ANALOG)
|
||||
#define VOLT_DIV_R1 10000
|
||||
#define VOLT_DIV_R2 2370
|
||||
#define VOLT_DIV_FAC ((float)VOLT_DIV_R2 / (VOLT_DIV_R2 + VOLT_DIV_R1))
|
||||
|
|
@ -1781,27 +1786,24 @@ static void lcd_menu_temperatures()
|
|||
//! | |
|
||||
//! | PWR: 00.0V | c=12 r=1
|
||||
//! | Bed: 00.0V | c=12 r=1
|
||||
//! | |
|
||||
//! | IR : 00.0V | c=12 r=1 optional
|
||||
//! ----------------------
|
||||
//! @endcode
|
||||
//! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations.
|
||||
static void lcd_menu_voltages()
|
||||
{
|
||||
lcd_timeoutToStatus.stop(); //infinite timeout
|
||||
float volt_pwr = VOLT_DIV_REF * ((float)current_voltage_raw_pwr / (1023 * OVERSAMPLENR)) / VOLT_DIV_FAC;
|
||||
float volt_bed = VOLT_DIV_REF * ((float)current_voltage_raw_bed / (1023 * OVERSAMPLENR)) / VOLT_DIV_FAC;
|
||||
lcd_home();
|
||||
#if !IR_SENSOR_ANALOG
|
||||
lcd_printf_P(PSTR("\n"));
|
||||
#endif //!IR_SENSOR_ANALOG
|
||||
lcd_printf_P(PSTR(" PWR: %4.1fV\n" " BED: %4.1fV"), volt_pwr, volt_bed);
|
||||
#if IR_SENSOR_ANALOG
|
||||
float volt_IR = VOLT_DIV_REF * ((float)current_voltage_raw_IR / (1023 * OVERSAMPLENR));
|
||||
lcd_printf_P(PSTR("\n IR : %3.1fV"),volt_IR);
|
||||
lcd_timeoutToStatus.stop(); //infinite timeout
|
||||
float volt_pwr = VOLT_DIV_REF * ((float)current_voltage_raw_pwr / (1023 * OVERSAMPLENR)) / VOLT_DIV_FAC;
|
||||
float volt_bed = VOLT_DIV_REF * ((float)current_voltage_raw_bed / (1023 * OVERSAMPLENR)) / VOLT_DIV_FAC;
|
||||
lcd_home();
|
||||
lcd_printf_P(PSTR(" PWR: %4.1fV\n" " BED: %4.1fV"), volt_pwr, volt_bed);
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
float volt_IR = VOLT_DIV_REF * ((float)current_voltage_raw_IR / (1023 * OVERSAMPLENR));
|
||||
lcd_printf_P(PSTR("\n IR : %3.1fV"),volt_IR);
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
menu_back_if_clicked();
|
||||
menu_back_if_clicked();
|
||||
}
|
||||
#endif //defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || IR_SENSOR_ANALOG
|
||||
#endif //defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || defined(IR_SENSOR_ANALOG)
|
||||
|
||||
#ifdef TMC2130
|
||||
//! @brief Show Belt Status
|
||||
|
|
@ -1975,6 +1977,23 @@ static void lcd_support_menu()
|
|||
MENU_ITEM_BACK_P(_i("Date:"));////MSG_DATE c=17 r=1
|
||||
MENU_ITEM_BACK_P(PSTR(__DATE__));
|
||||
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
MENU_ITEM_BACK_P(STR_SEPARATOR);
|
||||
MENU_ITEM_BACK_P(PSTR("Fil. sensor v.:"));
|
||||
switch(oFsensorPCB)
|
||||
{
|
||||
case ClFsensorPCB::_Old:
|
||||
MENU_ITEM_BACK_P(PSTR(" 03 or older"));
|
||||
break;
|
||||
case ClFsensorPCB::_Rev03b:
|
||||
MENU_ITEM_BACK_P(PSTR(" 03b or newer"));
|
||||
break;
|
||||
case ClFsensorPCB::_Undef:
|
||||
default:
|
||||
MENU_ITEM_BACK_P(PSTR(" state unknown"));
|
||||
}
|
||||
#endif // IR_SENSOR_ANALOG
|
||||
|
||||
MENU_ITEM_BACK_P(STR_SEPARATOR);
|
||||
if (mmu_enabled)
|
||||
{
|
||||
|
|
@ -5445,7 +5464,7 @@ SETTINGS_VERSION;
|
|||
MENU_END();
|
||||
}
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
static void lcd_fsensor_actionNA_set(void)
|
||||
{
|
||||
switch(oFsensorActionNA)
|
||||
|
|
@ -5511,8 +5530,9 @@ void lcd_hw_setup_menu(void) // can not be "static"
|
|||
SETTINGS_NOZZLE;
|
||||
MENU_ITEM_SUBMENU_P(_i("Checks"), lcd_checking_menu);
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
FSENSOR_ACTION_NA;
|
||||
MENU_ITEM_FUNCTION_P(PSTR("Fsensor Detection"), lcd_detect_IRsensor);
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
MENU_END();
|
||||
}
|
||||
|
|
@ -6931,7 +6951,7 @@ static void lcd_tune_menu()
|
|||
else {
|
||||
MENU_ITEM_TOGGLE_P(_T(MSG_FSENSOR), _T(MSG_ON), lcd_fsensor_state_set);
|
||||
}
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
FSENSOR_ACTION_NA;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
#endif //FILAMENT_SENSOR
|
||||
|
|
@ -7167,10 +7187,7 @@ void lcd_print_stop()
|
|||
|
||||
planner_abort_hard(); //needs to be done since plan_buffer_line resets waiting_inside_plan_buffer_line_print_aborted to false. Also copies current to destination.
|
||||
|
||||
axis_relative_modes[X_AXIS] = false;
|
||||
axis_relative_modes[Y_AXIS] = false;
|
||||
axis_relative_modes[Z_AXIS] = false;
|
||||
axis_relative_modes[E_AXIS] = true;
|
||||
axis_relative_modes = E_AXIS_MASK; //XYZ absolute, E relative
|
||||
|
||||
isPrintPaused = false; //clear isPrintPaused flag to allow starting next print after pause->stop scenario.
|
||||
}
|
||||
|
|
@ -7359,73 +7376,95 @@ void lcd_belttest_print(const char* msg, uint16_t X, uint16_t Y)
|
|||
}
|
||||
void lcd_belttest()
|
||||
{
|
||||
int _progress = 0;
|
||||
bool _result = true;
|
||||
|
||||
#ifdef TMC2130 // Belttest requires high power mode. Enable it.
|
||||
FORCE_HIGH_POWER_START;
|
||||
#endif
|
||||
|
||||
uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
|
||||
uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
|
||||
lcd_belttest_print(_i("Checking X..."), X, Y);
|
||||
|
||||
_delay(2000);
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
|
||||
_result = lcd_selfcheck_axis_sg(X_AXIS);
|
||||
X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
|
||||
if (!_result){
|
||||
lcd_belttest_print(_i("Error"), X, Y);
|
||||
return;
|
||||
if (_result){
|
||||
lcd_belttest_print(_i("Checking Y..."), X, Y);
|
||||
_result = lcd_selfcheck_axis_sg(Y_AXIS);
|
||||
Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
|
||||
}
|
||||
|
||||
lcd_belttest_print(_i("Checking Y..."), X, Y);
|
||||
_result = lcd_selfcheck_axis_sg(Y_AXIS);
|
||||
Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
|
||||
|
||||
if (!_result){
|
||||
|
||||
if (!_result) {
|
||||
lcd_belttest_print(_i("Error"), X, Y);
|
||||
lcd_clear();
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
lcd_belttest_print(_i("Done"), X, Y);
|
||||
} else {
|
||||
lcd_belttest_print(_i("Done"), X, Y);
|
||||
}
|
||||
|
||||
#ifdef TMC2130
|
||||
FORCE_HIGH_POWER_END;
|
||||
#endif
|
||||
|
||||
KEEPALIVE_STATE(NOT_BUSY);
|
||||
_delay(3000);
|
||||
}
|
||||
#endif //TMC2130
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
static bool lcd_selftest_IRsensor()
|
||||
{
|
||||
bool bAction;
|
||||
bool bPCBrev03b;
|
||||
uint16_t volt_IR_int;
|
||||
float volt_IR;
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
// called also from marlin_main.cpp
|
||||
void printf_IRSensorAnalogBoardChange(bool bPCBrev03b){
|
||||
printf_P(PSTR("Filament sensor board change detected: revision %S\n"), bPCBrev03b ? PSTR("03b or newer") : PSTR("03 or older"));
|
||||
}
|
||||
|
||||
volt_IR_int=current_voltage_raw_IR;
|
||||
bPCBrev03b=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD));
|
||||
volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR));
|
||||
printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR);
|
||||
if(volt_IR_int<((int)IRsensor_Hmin_TRESHOLD))
|
||||
{
|
||||
lcd_selftest_error(TestError::FsensorLevel,"HIGH","");
|
||||
return(false);
|
||||
}
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob."));
|
||||
volt_IR_int=current_voltage_raw_IR;
|
||||
volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR));
|
||||
printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR);
|
||||
if(volt_IR_int>((int)IRsensor_Lmax_TRESHOLD))
|
||||
{
|
||||
lcd_selftest_error(TestError::FsensorLevel,"LOW","");
|
||||
return(false);
|
||||
}
|
||||
if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB) // safer then "(uint8_t)bPCBrev03b"
|
||||
{
|
||||
printf_P(PSTR("Filament sensor board change detected: revision %S\n"),bPCBrev03b?PSTR("03b or newer"):PSTR("03 or older"));
|
||||
oFsensorPCB=bPCBrev03b?ClFsensorPCB::_Rev03b:ClFsensorPCB::_Old;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB);
|
||||
}
|
||||
return(true);
|
||||
static bool lcd_selftest_IRsensor(bool bStandalone)
|
||||
{
|
||||
bool bAction;
|
||||
bool bPCBrev03b;
|
||||
uint16_t volt_IR_int;
|
||||
float volt_IR;
|
||||
|
||||
volt_IR_int=current_voltage_raw_IR;
|
||||
bPCBrev03b=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD));
|
||||
volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR));
|
||||
printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR);
|
||||
if(volt_IR_int < ((int)IRsensor_Hmin_TRESHOLD)){
|
||||
if(!bStandalone)
|
||||
lcd_selftest_error(TestError::FsensorLevel,"HIGH","");
|
||||
return(false);
|
||||
}
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob."));
|
||||
volt_IR_int=current_voltage_raw_IR;
|
||||
volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR));
|
||||
printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR);
|
||||
if(volt_IR_int > ((int)IRsensor_Lmax_TRESHOLD)){
|
||||
if(!bStandalone)
|
||||
lcd_selftest_error(TestError::FsensorLevel,"LOW","");
|
||||
return(false);
|
||||
}
|
||||
if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB){ // safer then "(uint8_t)bPCBrev03b"
|
||||
printf_IRSensorAnalogBoardChange(bPCBrev03b);
|
||||
oFsensorPCB=bPCBrev03b?ClFsensorPCB::_Rev03b:ClFsensorPCB::_Old;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB);
|
||||
}
|
||||
return(true);
|
||||
}
|
||||
|
||||
static void lcd_detect_IRsensor(){
|
||||
bool bAction;
|
||||
|
||||
bMenuFSDetect = true; // inhibits some code inside "manage_inactivity()"
|
||||
bAction = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament loaded?"), false, false);
|
||||
if(bAction){
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Please unload the filament first, then repeat this action."));
|
||||
return;
|
||||
}
|
||||
bAction = lcd_selftest_IRsensor(true);
|
||||
if(bAction)
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Sensor verified, remove the filament now."));
|
||||
else
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Verification failed, remove the filament and try again."));
|
||||
bMenuFSDetect=false; // de-inhibits some code inside "manage_inactivity()"
|
||||
}
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
|
|
@ -7439,7 +7478,8 @@ bool lcd_selftest()
|
|||
int _progress = 0;
|
||||
bool _result = true;
|
||||
bool _swapped_fan = false;
|
||||
#if IR_SENSOR_ANALOG
|
||||
//#ifdef IR_SENSOR_ANALOG
|
||||
#if (0)
|
||||
bool bAction;
|
||||
bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true);
|
||||
if(!bAction)
|
||||
|
|
@ -7451,10 +7491,7 @@ bool lcd_selftest()
|
|||
#ifdef TMC2130
|
||||
FORCE_HIGH_POWER_START;
|
||||
#endif // TMC2130
|
||||
_delay(2000);
|
||||
|
||||
FORCE_BL_ON_START;
|
||||
|
||||
FORCE_BL_ON_START;
|
||||
_delay(2000);
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
|
|
@ -7522,11 +7559,7 @@ bool lcd_selftest()
|
|||
if (_result)
|
||||
{
|
||||
_progress = lcd_selftest_screen(TestScreen::FansOk, _progress, 3, true, 2000);
|
||||
#ifndef TMC2130
|
||||
_result = lcd_selfcheck_endstops();
|
||||
#else
|
||||
_result = true;
|
||||
#endif
|
||||
_result = lcd_selfcheck_endstops(); //With TMC2130, only the Z probe is tested.
|
||||
}
|
||||
|
||||
if (_result)
|
||||
|
|
@ -7577,21 +7610,31 @@ bool lcd_selftest()
|
|||
#ifdef TMC2130
|
||||
tmc2130_home_exit();
|
||||
enable_endstops(false);
|
||||
current_position[X_AXIS] = current_position[X_AXIS] + 14;
|
||||
current_position[Y_AXIS] = current_position[Y_AXIS] + 12;
|
||||
#endif
|
||||
|
||||
//homeaxis(X_AXIS);
|
||||
//homeaxis(Y_AXIS);
|
||||
current_position[X_AXIS] += pgm_read_float(bed_ref_points_4);
|
||||
current_position[Y_AXIS] += pgm_read_float(bed_ref_points_4+1);
|
||||
#ifdef TMC2130
|
||||
//current_position[X_AXIS] += 0;
|
||||
current_position[Y_AXIS] += 4;
|
||||
#endif //TMC2130
|
||||
current_position[Z_AXIS] = current_position[Z_AXIS] + 10;
|
||||
plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
|
||||
st_synchronize();
|
||||
set_destination_to_current();
|
||||
_progress = lcd_selftest_screen(TestScreen::AxisZ, _progress, 3, true, 1500);
|
||||
_result = lcd_selfcheck_axis(2, Z_MAX_POS);
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) != 1) {
|
||||
enquecommand_P(PSTR("G28 W"));
|
||||
enquecommand_P(PSTR("G1 Z15 F1000"));
|
||||
}
|
||||
#ifdef TMC2130
|
||||
homeaxis(Z_AXIS); //In case of failure, the code gets stuck in this function.
|
||||
#else
|
||||
_result = lcd_selfcheck_axis(Z_AXIS, Z_MAX_POS);
|
||||
#endif //TMC2130
|
||||
|
||||
//raise Z to not damage the bed during and hotend testing
|
||||
current_position[Z_AXIS] += 20;
|
||||
plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
|
||||
#ifdef TMC2130
|
||||
|
|
@ -7648,7 +7691,8 @@ bool lcd_selftest()
|
|||
_progress = lcd_selftest_screen(TestScreen::FsensorOk, _progress, 3, true, 2000); //fil sensor OK
|
||||
}
|
||||
#endif //PAT9125
|
||||
#if IR_SENSOR_ANALOG
|
||||
//#ifdef IR_SENSOR_ANALOG
|
||||
#if (0)
|
||||
_progress = lcd_selftest_screen(TestScreen::Fsensor, _progress, 3, true, 2000); //check filament sensor
|
||||
_result = lcd_selftest_IRsensor();
|
||||
if (_result)
|
||||
|
|
@ -7715,9 +7759,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
|
|||
enable_endstops(true);
|
||||
|
||||
if (axis == X_AXIS) { //there is collision between cables and PSU cover in X axis if Z coordinate is too low
|
||||
|
||||
current_position[Z_AXIS] += 17;
|
||||
plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
|
||||
raise_z_above(17,true);
|
||||
tmc2130_home_enter(Z_AXIS_MASK);
|
||||
st_synchronize();
|
||||
tmc2130_home_exit();
|
||||
|
|
@ -7814,7 +7856,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
|
|||
}
|
||||
#endif //TMC2130
|
||||
|
||||
//#ifndef TMC2130
|
||||
#ifndef TMC2130
|
||||
|
||||
static bool lcd_selfcheck_axis(int _axis, int _travel)
|
||||
{
|
||||
|
|
@ -7913,12 +7955,13 @@ static bool lcd_selfcheck_axis(int _axis, int _travel)
|
|||
{
|
||||
lcd_selftest_error(TestError::Motor, _error_1, _error_2);
|
||||
}
|
||||
}
|
||||
}
|
||||
current_position[_axis] = 0; //simulate axis home to avoid negative numbers for axis position, especially Z.
|
||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||
|
||||
return _stepresult;
|
||||
}
|
||||
|
||||
#ifndef TMC2130
|
||||
static bool lcd_selfcheck_pulleys(int axis)
|
||||
{
|
||||
float tmp_motor_loud[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
|
||||
|
|
@ -7963,9 +8006,6 @@ static bool lcd_selfcheck_pulleys(int axis)
|
|||
((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1)) {
|
||||
endstop_triggered = true;
|
||||
if (current_position_init - 1 <= current_position[axis] && current_position_init + 1 >= current_position[axis]) {
|
||||
current_position[axis] += (axis == X_AXIS) ? 13 : 9;
|
||||
plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
|
||||
st_synchronize();
|
||||
return(true);
|
||||
}
|
||||
else {
|
||||
|
|
@ -7985,31 +8025,42 @@ static bool lcd_selfcheck_pulleys(int axis)
|
|||
}
|
||||
return(true);
|
||||
}
|
||||
#endif //not defined TMC2130
|
||||
|
||||
|
||||
static bool lcd_selfcheck_endstops()
|
||||
{
|
||||
bool _result = true;
|
||||
|
||||
if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
|
||||
if (
|
||||
#ifndef TMC2130
|
||||
((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
|
||||
((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) ||
|
||||
#endif //!TMC2130
|
||||
((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1))
|
||||
{
|
||||
#ifndef TMC2130
|
||||
if ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) current_position[0] += 10;
|
||||
if ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) current_position[1] += 10;
|
||||
#endif //!TMC2130
|
||||
if ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1) current_position[2] += 10;
|
||||
}
|
||||
plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
|
||||
_delay(500);
|
||||
st_synchronize();
|
||||
|
||||
if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
|
||||
if (
|
||||
#ifndef TMC2130
|
||||
((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
|
||||
((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) ||
|
||||
#endif //!TMC2130
|
||||
((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1))
|
||||
{
|
||||
_result = false;
|
||||
char _error[4] = "";
|
||||
#ifndef TMC2130
|
||||
if ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "X");
|
||||
if ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "Y");
|
||||
#endif //!TMC2130
|
||||
if ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "Z");
|
||||
lcd_selftest_error(TestError::Endstops, _error, "");
|
||||
}
|
||||
|
|
@ -8017,7 +8068,6 @@ static bool lcd_selfcheck_endstops()
|
|||
manage_inactivity(true);
|
||||
return _result;
|
||||
}
|
||||
#endif //not defined TMC2130
|
||||
|
||||
static bool lcd_selfcheck_check_heater(bool _isbed)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -55,8 +55,10 @@ extern bool lcd_selftest();
|
|||
|
||||
void lcd_menu_statistics();
|
||||
|
||||
void lcd_status_screen(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
void lcd_menu_extruder_info(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
void lcd_menu_show_sensors_state(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
|
||||
#ifdef TMC2130
|
||||
bool lcd_crash_detect_enabled();
|
||||
void lcd_crash_detect_enable();
|
||||
|
|
@ -138,6 +140,11 @@ extern uint8_t farm_status;
|
|||
#define SILENT_MODE_OFF SILENT_MODE_POWER
|
||||
#endif
|
||||
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
extern bool bMenuFSDetect;
|
||||
void printf_IRSensorAnalogBoardChange(bool bPCBrev03b);
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
extern int8_t SilentModeMenu;
|
||||
extern uint8_t SilentModeMenu_MMU;
|
||||
|
||||
|
|
@ -250,7 +257,7 @@ enum class WizState : uint8_t
|
|||
void lcd_wizard(WizState state);
|
||||
|
||||
#define VOLT_DIV_REF 5
|
||||
#if IR_SENSOR_ANALOG
|
||||
#ifdef IR_SENSOR_ANALOG
|
||||
#define IRsensor_Hmin_TRESHOLD (3.0*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~3.0V (0.6*Vcc)
|
||||
#define IRsensor_Lmax_TRESHOLD (1.5*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~1.5V (0.3*Vcc)
|
||||
#define IRsensor_Hopen_TRESHOLD (4.6*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~4.6V (N.C. @ Ru~20-50k, Rd'=56k, Ru'=10k)
|
||||
|
|
|
|||
|
|
@ -21,7 +21,7 @@
|
|||
- For MK3 --> skip to step 3.
|
||||
- If you have a different printer model, follow step [2.b](#2b) from Windows build
|
||||
|
||||
3. Run `sudo ./build.sh`
|
||||
3. Run `./build.sh`
|
||||
- Output hex file is at `"PrusaFirmware/lang/firmware.hex"` . In the same folder you can hex files for other languages as well.
|
||||
|
||||
4. Connect your printer and flash with PrusaSlicer ( Configuration --> Flash printer firmware ) or Slic3r PE.
|
||||
|
|
|
|||
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#MSG_CRASH_DET_STEALTH_FORCE_OFF c=20 r=4
|
||||
"WARNING:\x0aCrash detection\x0adisabled in\x0aStealth mode"
|
||||
"ATTENTION:\x0aDetection de crash\x0adesactivee en\x0amode feutre"
|
||||
"ATTENTION:\x0aDetection de crash\x0adesactivee en\x0amode furtif"
|
||||
|
||||
#
|
||||
">Cancel"
|
||||
|
|
@ -550,7 +550,7 @@
|
|||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
"Feutre"
|
||||
"Furtif"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
|
|
|
|||
Loading…
Reference in New Issue