Merge branch 'MK3' into print_fan_speed

This commit is contained in:
PavelSindler 2017-10-26 18:04:38 +02:00 committed by GitHub
commit d37c925bc0
21 changed files with 79946 additions and 7568 deletions

View File

@ -4,8 +4,14 @@
#include "boards.h" #include "boards.h"
#include "Configuration_prusa.h" #include "Configuration_prusa.h"
#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
// Firmware version // Firmware version
#define FW_version "3.0.12-RC2" #define FW_version "3.0.12-RC2"
#define FW_build 104
#define FW_version_build FW_version " b" STR(FW_build)
#define FW_PRUSA3D_MAGIC "PRUSA3DFW" #define FW_PRUSA3D_MAGIC "PRUSA3DFW"
#define FW_PRUSA3D_MAGIC_LEN 10 #define FW_PRUSA3D_MAGIC_LEN 10
@ -64,6 +70,12 @@
#define EEPROM_CRASH_DET (EEPROM_UVLO_MESH_BED_LEVELING-12) #define EEPROM_CRASH_DET (EEPROM_UVLO_MESH_BED_LEVELING-12)
// Filament sensor on/off EEPROM setting // Filament sensor on/off EEPROM setting
#define EEPROM_FSENSOR (EEPROM_UVLO_MESH_BED_LEVELING-14) #define EEPROM_FSENSOR (EEPROM_UVLO_MESH_BED_LEVELING-14)
// Crash detection counter
#define EEPROM_CRASH_COUNT (EEPROM_UVLO_MESH_BED_LEVELING-15)
// Filament runout/error coutner
#define EEPROM_FERROR_COUNT (EEPROM_UVLO_MESH_BED_LEVELING-16)
// Power loss errors
#define EEPROM_POWER_COUNT (EEPROM_UVLO_MESH_BED_LEVELING-17)
// Currently running firmware, each digit stored as uint16_t. // Currently running firmware, each digit stored as uint16_t.
// The flavor differentiates a dev, alpha, beta, release candidate or a release version. // The flavor differentiates a dev, alpha, beta, release candidate or a release version.

View File

@ -32,7 +32,8 @@
// Steps per unit {X,Y,Z,E} // Steps per unit {X,Y,Z,E}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140} //#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280} //#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,560}
// Endstop inverting // Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop. const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
@ -76,9 +77,13 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define Z_AXIS_ALWAYS_ON 1 #define Z_AXIS_ALWAYS_ON 1
// Automatic recovery after crash is detected
#define AUTOMATIC_RECOVERY_AFTER_CRASH
//DEBUG //DEBUG
#define DEBUG_DCODES //D codes #define DEBUG_DCODES //D codes
#if 1 #if 1
#define DEBUG_FSENSOR_LOG //Reports fsensor status to serial
//#define DEBUG_CRASHDET_COUNTERS //Display crash-detection counters on LCD //#define DEBUG_CRASHDET_COUNTERS //Display crash-detection counters on LCD
//#define DEBUG_RESUME_PRINT //Resume/save print debug enable //#define DEBUG_RESUME_PRINT //Resume/save print debug enable
//#define DEBUG_UVLO_AUTOMATIC_RECOVER // Power panic automatic recovery debug output //#define DEBUG_UVLO_AUTOMATIC_RECOVER // Power panic automatic recovery debug output
@ -107,7 +112,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes #define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis #define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis #define TMC2130_USTEPS_E 64 // microstep resolution for E axis
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes #define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis #define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis #define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
@ -157,8 +162,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing) #define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only) //new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes #define TMC2130_CURRENTS_H {3, 3, 5, 12} // default holding currents for all axes
#define TMC2130_CURRENTS_R {13, 20, 20, 22} // default running currents for all axes #define TMC2130_CURRENTS_R {13, 20, 20, 28} // default running currents for all axes
//#define TMC2130_DEBUG //#define TMC2130_DEBUG
//#define TMC2130_DEBUG_WR //#define TMC2130_DEBUG_WR

View File

@ -1,6 +1,7 @@
#include "Dcodes.h" #include "Dcodes.h"
#include "Marlin.h" #include "Marlin.h"
#include "cmdqueue.h" #include "cmdqueue.h"
#include "pat9125.h"
inline void serial_print_hex_nibble(uint8_t val) inline void serial_print_hex_nibble(uint8_t val)
{ {
@ -189,4 +190,57 @@ void dcode_4()
} }
} }
void dcode_9125()
{
MYSERIAL.println("D9125 - PAT9125");
if ((strchr_pointer[1+4] == '?') || (strchr_pointer[1+4] == 0))
{
MYSERIAL.print("res_x=");
MYSERIAL.print(pat9125_xres, DEC);
MYSERIAL.print(" res_y=");
MYSERIAL.print(pat9125_yres, DEC);
MYSERIAL.print(" x=");
MYSERIAL.print(pat9125_x, DEC);
MYSERIAL.print(" y=");
MYSERIAL.print(pat9125_y, DEC);
MYSERIAL.print(" b=");
MYSERIAL.print(pat9125_b, DEC);
MYSERIAL.print(" s=");
MYSERIAL.println(pat9125_s, DEC);
return;
}
if (strchr_pointer[1+4] == '!')
{
pat9125_update();
MYSERIAL.print("x=");
MYSERIAL.print(pat9125_x, DEC);
MYSERIAL.print(" y=");
MYSERIAL.print(pat9125_y, DEC);
MYSERIAL.print(" b=");
MYSERIAL.print(pat9125_b, DEC);
MYSERIAL.print(" s=");
MYSERIAL.println(pat9125_s, DEC);
return;
}
if (code_seen('R'))
{
unsigned char res = (int)code_value();
MYSERIAL.print("pat9125_init(xres=yres=");
MYSERIAL.print(res, DEC);
MYSERIAL.print(")=");
MYSERIAL.println(pat9125_init(res, res), DEC);
}
if (code_seen('X'))
{
pat9125_x = (int)code_value();
MYSERIAL.print("pat9125_x=");
MYSERIAL.print(pat9125_x, DEC);
}
if (code_seen('Y'))
{
pat9125_y = (int)code_value();
MYSERIAL.print("pat9125_y=");
MYSERIAL.print(pat9125_y, DEC);
}
}

View File

@ -7,5 +7,7 @@ extern void dcode_2();
extern void dcode_3(); extern void dcode_3();
extern void dcode_4(); extern void dcode_4();
extern void dcode_9125();
#endif //DCODES_H #endif //DCODES_H

View File

@ -23,7 +23,7 @@
#include "Marlin.h" #include "Marlin.h"
#include "MarlinSerial.h" #include "MarlinSerial.h"
int selectedSerialPort = 0; uint8_t selectedSerialPort = 0;
#ifndef AT90USB #ifndef AT90USB
// this next line disables the entire HardwareSerial.cpp, // this next line disables the entire HardwareSerial.cpp,
@ -58,23 +58,23 @@ FORCE_INLINE void store_char(unsigned char c)
// Test for a framing error. // Test for a framing error.
if (M_UCSRxA & (1<<M_FEx)) { if (M_UCSRxA & (1<<M_FEx)) {
// Characters received with the framing errors will be ignored. // Characters received with the framing errors will be ignored.
// The temporary variable "c" was made volatile, so the compiler does not optimize this out. // Dummy register read (discard)
volatile unsigned char c = M_UDRx; (void)(*(char *)M_UDRx);
} else { } else {
// Read the input register. // Read the input register.
unsigned char c = M_UDRx; unsigned char c = M_UDRx;
store_char(c); store_char(c);
} }
} }
#ifndef SNMM
SIGNAL(USART2_RX_vect) SIGNAL(USART2_RX_vect)
{ {
if (selectedSerialPort == 1) { if (selectedSerialPort == 1) {
// Test for a framing error. // Test for a framing error.
if (UCSR2A & (1<<FE2)) { if (UCSR2A & (1<<FE2)) {
// Characters received with the framing errors will be ignored. // Characters received with the framing errors will be ignored.
// The temporary variable "c" was made volatile, so the compiler does not optimize this out. // Dummy register read (discard)
volatile unsigned char c = UDR2; (void)(*(char *)UDR2);
} else { } else {
// Read the input register. // Read the input register.
unsigned char c = UDR2; unsigned char c = UDR2;
@ -84,6 +84,7 @@ FORCE_INLINE void store_char(unsigned char c)
} }
} }
#endif #endif
#endif
// Constructors //////////////////////////////////////////////////////////////// // Constructors ////////////////////////////////////////////////////////////////
@ -124,8 +125,9 @@ void MarlinSerial::begin(long baud)
sbi(M_UCSRxB, M_TXENx); sbi(M_UCSRxB, M_TXENx);
sbi(M_UCSRxB, M_RXCIEx); sbi(M_UCSRxB, M_RXCIEx);
#ifndef SNMM
// set up the second serial port if (selectedSerialPort == 1) { //set up also the second serial port
if (useU2X) { if (useU2X) {
UCSR2A = 1 << U2X2; UCSR2A = 1 << U2X2;
baud_setting = (F_CPU / 4 / baud - 1) / 2; baud_setting = (F_CPU / 4 / baud - 1) / 2;
@ -142,6 +144,8 @@ void MarlinSerial::begin(long baud)
sbi(UCSR2B, TXEN2); sbi(UCSR2B, TXEN2);
sbi(UCSR2B, RXCIE2); sbi(UCSR2B, RXCIE2);
} }
#endif
}
void MarlinSerial::end() void MarlinSerial::end()
{ {
@ -149,9 +153,11 @@ void MarlinSerial::end()
cbi(M_UCSRxB, M_TXENx); cbi(M_UCSRxB, M_TXENx);
cbi(M_UCSRxB, M_RXCIEx); cbi(M_UCSRxB, M_RXCIEx);
#ifndef SNMM
cbi(UCSR2B, RXEN2); cbi(UCSR2B, RXEN2);
cbi(UCSR2B, TXEN2); cbi(UCSR2B, TXEN2);
cbi(UCSR2B, RXCIE2); cbi(UCSR2B, RXCIE2);
#endif
} }

View File

@ -73,7 +73,7 @@
// is the index of the location from which to read. // is the index of the location from which to read.
#define RX_BUFFER_SIZE 128 #define RX_BUFFER_SIZE 128
extern int selectedSerialPort; extern uint8_t selectedSerialPort;
struct ring_buffer struct ring_buffer
{ {

View File

@ -70,6 +70,7 @@
#ifdef PAT9125 #ifdef PAT9125
#include "pat9125.h" #include "pat9125.h"
#include "fsensor.h"
#endif //PAT9125 #endif //PAT9125
#ifdef TMC2130 #ifdef TMC2130
@ -613,117 +614,6 @@ void crashdet_stop_and_save_print2()
} }
#ifdef PAT9125
void fsensor_stop_and_save_print()
{
// stop_and_save_print_to_ram(10, -0.8); //XY - no change, Z 10mm up, E 0.8mm in
stop_and_save_print_to_ram(0, 0); //XYZE - no change
}
void fsensor_restore_print_and_continue()
{
restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change
}
bool fsensor_enabled = true;
bool fsensor_ignore_error = true;
bool fsensor_M600 = false;
long fsensor_prev_pos_e = 0;
uint8_t fsensor_err_cnt = 0;
#define FSENS_ESTEPS 280 //extruder resolution [steps/mm]
//#define FSENS_MINDEL 560 //filament sensor min delta [steps] (3mm)
#define FSENS_MINDEL 280 //filament sensor min delta [steps] (3mm)
#define FSENS_MINFAC 3 //filament sensor minimum factor [count/mm]
//#define FSENS_MAXFAC 50 //filament sensor maximum factor [count/mm]
#define FSENS_MAXFAC 40 //filament sensor maximum factor [count/mm]
//#define FSENS_MAXERR 2 //filament sensor max error count
#define FSENS_MAXERR 5 //filament sensor max error count
extern int8_t FSensorStateMenu;
void fsensor_enable()
{
MYSERIAL.println("fsensor_enable");
pat9125_y = 0;
fsensor_prev_pos_e = st_get_position(E_AXIS);
fsensor_err_cnt = 0;
fsensor_enabled = true;
fsensor_ignore_error = true;
fsensor_M600 = false;
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0xFF);
FSensorStateMenu = 1;
}
void fsensor_disable()
{
MYSERIAL.println("fsensor_disable");
fsensor_enabled = false;
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0x00);
FSensorStateMenu = 0;
}
void fsensor_update()
{
if (!fsensor_enabled) return;
long pos_e = st_get_position(E_AXIS); //current position
pat9125_update();
long del_e = pos_e - fsensor_prev_pos_e; //delta
if (abs(del_e) < FSENS_MINDEL) return;
float de = ((float)del_e / FSENS_ESTEPS);
int cmin = de * FSENS_MINFAC;
int cmax = de * FSENS_MAXFAC;
int cnt = -pat9125_y;
fsensor_prev_pos_e = pos_e;
pat9125_y = 0;
bool err = false;
if ((del_e > 0) && ((cnt < cmin) || (cnt > cmax))) err = true;
if ((del_e < 0) && ((cnt > cmin) || (cnt < cmax))) err = true;
if (err)
fsensor_err_cnt++;
else
fsensor_err_cnt = 0;
/**/
MYSERIAL.print("pos_e=");
MYSERIAL.print(pos_e);
MYSERIAL.print(" de=");
MYSERIAL.print(de);
MYSERIAL.print(" cmin=");
MYSERIAL.print((int)cmin);
MYSERIAL.print(" cmax=");
MYSERIAL.print((int)cmax);
MYSERIAL.print(" cnt=");
MYSERIAL.print((int)cnt);
MYSERIAL.print(" err=");
MYSERIAL.println((int)fsensor_err_cnt);/**/
// return;
if (fsensor_err_cnt > FSENS_MAXERR)
{
MYSERIAL.println("fsensor_update (fsensor_err_cnt > FSENS_MAXERR)");
if (fsensor_ignore_error)
{
MYSERIAL.println("fsensor_update - error ignored)");
fsensor_ignore_error = false;
}
else
{
MYSERIAL.println("fsensor_update - ERROR!!!");
fsensor_stop_and_save_print();
enquecommand_front_P((PSTR("M600")));
fsensor_M600 = true;
fsensor_enabled = false;
}
}
}
#endif //PAT9125
#ifdef MESH_BED_LEVELING #ifdef MESH_BED_LEVELING
enum MeshLevelingState { MeshReport, MeshStart, MeshNext, MeshSet }; enum MeshLevelingState { MeshReport, MeshStart, MeshNext, MeshSet };
@ -917,9 +807,10 @@ void setup()
#ifdef PAT9125 #ifdef PAT9125
MYSERIAL.print("PAT9125_init:"); MYSERIAL.print("PAT9125_init:");
MYSERIAL.println(pat9125_init(200, 200)); int pat9125 = pat9125_init(200, 200);
MYSERIAL.println(pat9125);
uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR); uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR);
if (!pat9125) fsensor = 0; //disable sensor
if (fsensor) if (fsensor)
{ {
fsensor_enable(); fsensor_enable();
@ -1101,6 +992,8 @@ void setup()
check_babystep(); //checking if Z babystep is in allowed range check_babystep(); //checking if Z babystep is in allowed range
setup_uvlo_interrupt(); setup_uvlo_interrupt();
setup_fan_interrupt(); setup_fan_interrupt();
fsensor_setup_interrupt();
#ifndef DEBUG_DISABLE_STARTMSGS #ifndef DEBUG_DISABLE_STARTMSGS
@ -4482,6 +4375,8 @@ Sigma_Exit:
SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]); SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:"); SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]); SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(float(st_get_position(E_AXIS))/axis_steps_per_unit[E_AXIS]);
SERIAL_PROTOCOLLN(""); SERIAL_PROTOCOLLN("");
break; break;
@ -5824,6 +5719,8 @@ case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or disp
dcode_3(); break; dcode_3(); break;
case 4: // D4 - Read/Write PIN case 4: // D4 - Read/Write PIN
dcode_4(); break; dcode_4(); break;
case 9125: // D9125 - PAT9125
dcode_9125(); break;
case 5: case 5:
MYSERIAL.println("D5 - Test"); MYSERIAL.println("D5 - Test");
if (code_seen('P')) if (code_seen('P'))
@ -5834,6 +5731,11 @@ case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or disp
case 10: // D10 - Tell the printer that XYZ calibration went OK case 10: // D10 - Tell the printer that XYZ calibration went OK
calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST); calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST);
break; break;
case 12: //D12 - Reset Filament error, Power loss and crash counter ( Do it before every print and you can get stats for the print )
eeprom_update_byte((uint8_t*)EEPROM_CRASH_COUNT, 0x00);
eeprom_update_byte((uint8_t*)EEPROM_FERROR_COUNT, 0x00);
eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, 0x00);
case 999: case 999:
{ {
MYSERIAL.println("D999 - crash"); MYSERIAL.println("D999 - crash");
@ -5848,7 +5750,17 @@ case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or disp
lcd_update_enable(true); lcd_update_enable(true);
lcd_implementation_clear(); lcd_implementation_clear();
lcd_update(2); lcd_update(2);
// Increment crash counter
uint8_t crash_count = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT);
crash_count++;
eeprom_update_byte((uint8_t*)EEPROM_CRASH_COUNT, crash_count);
#ifdef AUTOMATIC_RECOVERY_AFTER_CRASH
bool yesno = true;
#else
bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_CRASH_DETECTED, false); bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_CRASH_DETECTED, false);
#endif
lcd_update_enable(true); lcd_update_enable(true);
lcd_update(2); lcd_update(2);
lcd_setstatuspgm(WELCOME_MSG); lcd_setstatuspgm(WELCOME_MSG);
@ -7072,6 +6984,11 @@ void uvlo_()
#endif #endif
disable_z(); disable_z();
// Increment power failure counter
uint8_t power_count = eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT);
power_count++;
eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, power_count);
SERIAL_ECHOLNPGM("UVLO - end"); SERIAL_ECHOLNPGM("UVLO - end");
cli(); cli();
while(1); while(1);

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

162
Firmware/fsensor.cpp Normal file
View File

@ -0,0 +1,162 @@
#include "Marlin.h"
#ifdef PAT9125
#include "fsensor.h"
#include "pat9125.h"
#include "planner.h"
//#include "LiquidCrystal.h"
//extern LiquidCrystal lcd;
#define FSENSOR_ERR_MAX 5 //filament sensor max error count
#define FSENSOR_INT_PIN 63 //filament sensor interrupt pin
#define FSENSOR_CHUNK_LEN 560 //filament sensor chunk length in steps
extern void stop_and_save_print_to_ram(float z_move, float e_move);
extern void restore_print_from_ram_and_continue(float e_move);
extern int8_t FSensorStateMenu;
void fsensor_stop_and_save_print()
{
stop_and_save_print_to_ram(0, 0); //XYZE - no change
}
void fsensor_restore_print_and_continue()
{
restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change
}
uint8_t fsensor_int_pin = FSENSOR_INT_PIN;
int16_t fsensor_chunk_len = FSENSOR_CHUNK_LEN;
bool fsensor_enabled = true;
//bool fsensor_ignore_error = true;
bool fsensor_M600 = false;
uint8_t fsensor_err_cnt = 0;
int16_t fsensor_st_cnt = 0;
void fsensor_enable()
{
MYSERIAL.println("fsensor_enable");
fsensor_enabled = true;
// fsensor_ignore_error = true;
fsensor_M600 = false;
fsensor_err_cnt = 0;
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0xFF);
FSensorStateMenu = 1;
}
void fsensor_disable()
{
MYSERIAL.println("fsensor_disable");
fsensor_enabled = false;
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0x00);
FSensorStateMenu = 0;
}
void pciSetup(byte pin)
{
*digitalPinToPCMSK(pin) |= bit (digitalPinToPCMSKbit(pin)); // enable pin
PCIFR |= bit (digitalPinToPCICRbit(pin)); // clear any outstanding interrupt
PCICR |= bit (digitalPinToPCICRbit(pin)); // enable interrupt for the group
}
void fsensor_setup_interrupt()
{
uint8_t fsensor_int_pin = 63;
pinMode(fsensor_int_pin, OUTPUT);
digitalWrite(fsensor_int_pin, HIGH);
pciSetup(fsensor_int_pin);
}
ISR(PCINT2_vect)
{
// return;
int st_cnt = fsensor_st_cnt;
fsensor_st_cnt = 0;
sei();
*digitalPinToPCMSK(fsensor_int_pin) &= ~bit(digitalPinToPCMSKbit(fsensor_int_pin));
digitalWrite(fsensor_int_pin, HIGH);
*digitalPinToPCMSK(fsensor_int_pin) |= bit(digitalPinToPCMSKbit(fsensor_int_pin));
pat9125_update_y();
if (st_cnt != 0)
{
#ifdef DEBUG_FSENSOR_LOG
MYSERIAL.print("cnt=");
MYSERIAL.print(st_cnt, DEC);
MYSERIAL.print(" dy=");
MYSERIAL.print(pat9125_y, DEC);
#endif //DEBUG_FSENSOR_LOG
if (st_cnt != 0)
{
if( (pat9125_y == 0) || ((pat9125_y > 0) && (st_cnt < 0)) || ((pat9125_y < 0) && (st_cnt > 0)))
{ //invalid movement
fsensor_err_cnt++;
#ifdef DEBUG_FSENSOR_LOG
MYSERIAL.print("\tNG ! err=");
MYSERIAL.println(fsensor_err_cnt, DEC);
#endif //DEBUG_FSENSOR_LOG
}
else
{ //propper movement
if (fsensor_err_cnt > 0)
fsensor_err_cnt--;
#ifdef DEBUG_FSENSOR_LOG
MYSERIAL.print("\tOK err=");
MYSERIAL.println(fsensor_err_cnt, DEC);
#endif //DEBUG_FSENSOR_LOG
}
}
else
{ //no movement
#ifdef DEBUG_FSENSOR_LOG
MYSERIAL.println("\tOK 0");
#endif //DEBUG_FSENSOR_LOG
}
}
pat9125_y = 0;
return;
}
void fsensor_st_block_begin(block_t* bl)
{
if ((fsensor_st_cnt > 0) && (bl->direction_bits & 0x8))
digitalWrite(fsensor_int_pin, LOW);
if ((fsensor_st_cnt < 0) && !(bl->direction_bits & 0x8))
digitalWrite(fsensor_int_pin, LOW);
}
void fsensor_st_block_chunk(block_t* bl, int cnt)
{
fsensor_st_cnt += (bl->direction_bits & 0x8)?-cnt:cnt;
if ((fsensor_st_cnt >= fsensor_chunk_len) || (fsensor_st_cnt <= -fsensor_chunk_len))
digitalWrite(fsensor_int_pin, LOW);
}
void fsensor_update()
{
if (!fsensor_enabled) return;
if (fsensor_err_cnt > FSENSOR_ERR_MAX)
{
MYSERIAL.println("fsensor_update (fsensor_err_cnt > FSENSOR_ERR_MAX)");
/* if (fsensor_ignore_error)
{
MYSERIAL.println("fsensor_update - error ignored)");
fsensor_ignore_error = false;
}
else*/
{
MYSERIAL.println("fsensor_update - ERROR!!!");
fsensor_stop_and_save_print();
enquecommand_front_P((PSTR("M600")));
fsensor_M600 = true;
fsensor_enabled = false;
}
}
}
#endif //PAT9125

30
Firmware/fsensor.h Normal file
View File

@ -0,0 +1,30 @@
#ifndef FSENSOR_H
#define FSENSOR_H
#include "planner.h"
//save restore printing
extern void fsensor_stop_and_save_print();
extern void fsensor_restore_print_and_continue();
//enable/disable
extern void fsensor_enable();
extern void fsensor_disable();
//update (perform M600 on filament runout)
extern void fsensor_update();
//setup pin-change interrupt
extern void fsensor_setup_interrupt();
//callbacks from stepper
extern void fsensor_st_block_begin(block_t* bl);
extern void fsensor_st_block_chunk(block_t* bl, int cnt);
//minimum meassured chunk length in steps
extern int16_t fsensor_chunk_len;
//M600 in progress
extern bool fsensor_M600;
#endif //FSENSOR_H

View File

@ -10,13 +10,19 @@
#ifdef PAT9125_SWI2C #ifdef PAT9125_SWI2C
#include "swi2c.h" #include "swi2c.h"
#endif //PAT9125_SWI2C #endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
#include <Wire.h>
#endif //PAT9125_HWI2C
unsigned char pat9125_PID1 = 0; unsigned char pat9125_PID1 = 0;
unsigned char pat9125_PID2 = 0; unsigned char pat9125_PID2 = 0;
unsigned char pat9125_xres = 0;
unsigned char pat9125_yres = 0;
int pat9125_x = 0; int pat9125_x = 0;
int pat9125_y = 0; int pat9125_y = 0;
int pat9125_b = 0; unsigned char pat9125_b = 0;
unsigned char pat9125_s = 0;
int pat9125_init(unsigned char xres, unsigned char yres) int pat9125_init(unsigned char xres, unsigned char yres)
{ {
@ -26,14 +32,20 @@ int pat9125_init(unsigned char xres, unsigned char yres)
#ifdef PAT9125_SWI2C #ifdef PAT9125_SWI2C
swi2c_init(PAT9125_SWI2C_SDA, PAT9125_SWI2C_SCL, PAT9125_SWI2C_CFG); swi2c_init(PAT9125_SWI2C_SDA, PAT9125_SWI2C_SCL, PAT9125_SWI2C_CFG);
#endif //PAT9125_SWI2C #endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
Wire.begin();
#endif //PAT9125_HWI2C
pat9125_xres = xres;
pat9125_yres = yres;
pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1); pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2); pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2);
if ((pat9125_PID1 != 0x31) || (pat9125_PID2 != 0x91)) if ((pat9125_PID1 != 0x31) || (pat9125_PID2 != 0x91))
{ {
return 0; return 0;
} }
pat9125_wr_reg(PAT9125_RES_X, xres); pat9125_wr_reg(PAT9125_RES_X, pat9125_xres);
pat9125_wr_reg(PAT9125_RES_Y, yres); pat9125_wr_reg(PAT9125_RES_Y, pat9125_yres);
// pat9125_wr_reg(PAT9125_ORIENTATION, 0x04 | (xinv?0x08:0) | (yinv?0x10:0)); //!? direction switching does not work
return 1; return 1;
} }
@ -43,6 +55,7 @@ int pat9125_update()
{ {
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION); unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
pat9125_b = pat9125_rd_reg(PAT9125_FRAME); pat9125_b = pat9125_rd_reg(PAT9125_FRAME);
pat9125_s = pat9125_rd_reg(PAT9125_SHUTTER);
if (ucMotion & 0x80) if (ucMotion & 0x80)
{ {
unsigned char ucXL = pat9125_rd_reg(PAT9125_DELTA_XL); unsigned char ucXL = pat9125_rd_reg(PAT9125_DELTA_XL);
@ -53,7 +66,25 @@ int pat9125_update()
if (iDX & 0x800) iDX -= 4096; if (iDX & 0x800) iDX -= 4096;
if (iDY & 0x800) iDY -= 4096; if (iDY & 0x800) iDY -= 4096;
pat9125_x += iDX; pat9125_x += iDX;
pat9125_y += iDY; pat9125_y -= iDY; //negative number, because direction switching does not work
return 1;
}
}
return 0;
}
int pat9125_update_y()
{
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
{
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
if (ucMotion & 0x80)
{
unsigned char ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
unsigned char ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
if (iDY & 0x800) iDY -= 4096;
pat9125_y -= iDY; //negative number, because direction switching does not work
return 1; return 1;
} }
} }
@ -72,6 +103,14 @@ unsigned char pat9125_rd_reg(unsigned char addr)
#ifdef PAT9125_SWI2C #ifdef PAT9125_SWI2C
int iret = swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data); int iret = swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data);
#endif //PAT9125_SWI2C #endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
Wire.beginTransmission(PAT9125_I2C_ADDR);
Wire.write(addr);
Wire.endTransmission();
if (Wire.requestFrom(PAT9125_I2C_ADDR, 1) == 1)
// if (Wire.available())
data = Wire.read();
#endif //PAT9125_HWI2C
return data; return data;
} }
@ -86,6 +125,13 @@ void pat9125_wr_reg(unsigned char addr, unsigned char data)
#ifdef PAT9125_SWI2C #ifdef PAT9125_SWI2C
int iret = swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data); int iret = swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data);
#endif //PAT9125_SWI2C #endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
Wire.beginTransmission(PAT9125_I2C_ADDR);
Wire.write(addr);
Wire.write(data);
Wire.endTransmission();
#endif //PAT9125_HWI2C
} }
#endif //PAT9125 #endif //PAT9125

View File

@ -27,12 +27,17 @@
extern unsigned char pat9125_PID1; extern unsigned char pat9125_PID1;
extern unsigned char pat9125_PID2; extern unsigned char pat9125_PID2;
extern unsigned char pat9125_xres;
extern unsigned char pat9125_yres;
extern int pat9125_x; extern int pat9125_x;
extern int pat9125_y; extern int pat9125_y;
extern int pat9125_b; extern unsigned char pat9125_b;
extern unsigned char pat9125_s;
extern int pat9125_init(unsigned char xres, unsigned char yres); extern int pat9125_init(unsigned char xres, unsigned char yres);
extern int pat9125_update(); extern int pat9125_update();
extern int pat9125_update_y();
extern unsigned char pat9125_rd_reg(unsigned char addr); extern unsigned char pat9125_rd_reg(unsigned char addr);
extern void pat9125_wr_reg(unsigned char addr, unsigned char data); extern void pat9125_wr_reg(unsigned char addr, unsigned char data);

View File

@ -20,13 +20,15 @@
#define PAT9125_SWI2C_SCL 21 //SCL on P3 #define PAT9125_SWI2C_SCL 21 //SCL on P3
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout #define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
//#define PAT9125_HWI2C
#define X_TMC2130_CS 41 #define X_TMC2130_CS 41
#define X_TMC2130_DIAG 64 // !!! changed from 40 (EINY03) #define X_TMC2130_DIAG 64 // !!! changed from 40 (EINY03)
#define X_STEP_PIN 37 #define X_STEP_PIN 37
#define X_DIR_PIN 49 #define X_DIR_PIN 49
//#define X_MIN_PIN 12 #define X_MIN_PIN 12
//#define X_MAX_PIN 30 //#define X_MAX_PIN 30
#define X_MIN_PIN X_TMC2130_DIAG //#define X_MIN_PIN X_TMC2130_DIAG
#define X_MAX_PIN X_TMC2130_DIAG #define X_MAX_PIN X_TMC2130_DIAG
#define X_ENABLE_PIN 29 #define X_ENABLE_PIN 29
#define X_MS1_PIN -1 #define X_MS1_PIN -1
@ -36,9 +38,9 @@
#define Y_TMC2130_DIAG 69 #define Y_TMC2130_DIAG 69
#define Y_STEP_PIN 36 #define Y_STEP_PIN 36
#define Y_DIR_PIN 48 #define Y_DIR_PIN 48
//#define Y_MIN_PIN 11 #define Y_MIN_PIN 11
//#define Y_MAX_PIN 24 //#define Y_MAX_PIN 24
#define Y_MIN_PIN Y_TMC2130_DIAG //#define Y_MIN_PIN Y_TMC2130_DIAG
#define Y_MAX_PIN Y_TMC2130_DIAG #define Y_MAX_PIN Y_TMC2130_DIAG
#define Y_ENABLE_PIN 28 #define Y_ENABLE_PIN 28
#define Y_MS1_PIN -1 #define Y_MS1_PIN -1

View File

@ -37,7 +37,8 @@
#endif //TMC2130 #endif //TMC2130
#ifdef PAT9125 #ifdef PAT9125
extern uint8_t fsensor_err_cnt; #include "fsensor.h"
int fsensor_counter = 0; //counter for e-steps
#endif //PAT9125 #endif //PAT9125
//=========================================================================== //===========================================================================
@ -370,6 +371,10 @@ void isr() {
// Anything in the buffer? // Anything in the buffer?
current_block = plan_get_current_block(); current_block = plan_get_current_block();
if (current_block != NULL) { if (current_block != NULL) {
#ifdef PAT9125
fsensor_counter = 0;
fsensor_st_block_begin(current_block);
#endif //PAT9125
// The busy flag is set by the plan_get_current_block() call. // The busy flag is set by the plan_get_current_block() call.
// current_block->busy = true; // current_block->busy = true;
trapezoid_generator_reset(); trapezoid_generator_reset();
@ -436,12 +441,19 @@ void isr() {
CHECK_ENDSTOPS CHECK_ENDSTOPS
{ {
{ {
#if defined(X_MIN_PIN) && (X_MIN_PIN > -1) && !defined(DEBUG_DISABLE_XMINLIMIT) #if ( (defined(X_MIN_PIN) && (X_MIN_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_XMINLIMIT)
#ifdef TMC2130_SG_HOMING
// Stall guard homing turned on, now decide if software or hardware one
#ifndef TMC2130_SG_HOMING_SW_XY #ifndef TMC2130_SG_HOMING_SW_XY
x_min_endstop = (READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING); x_min_endstop = (READ(X_TMC2130_DIAG) != X_MIN_ENDSTOP_INVERTING);
#else //TMC2130_SG_HOMING_SW_XY #else //TMC2130_SG_HOMING_SW_XY
x_min_endstop = tmc2130_axis_stalled[X_AXIS]; x_min_endstop = tmc2130_axis_stalled[X_AXIS];
#endif //TMC2130_SG_HOMING_SW_XY #endif //TMC2130_SG_HOMING_SW_XY
#else
// Normal homing
x_min_endstop = (READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
#endif
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) { if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
endstops_trigsteps[X_AXIS] = count_position[X_AXIS]; endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true; endstop_x_hit=true;
@ -456,12 +468,19 @@ void isr() {
CHECK_ENDSTOPS CHECK_ENDSTOPS
{ {
{ {
#if defined(X_MAX_PIN) && (X_MAX_PIN > -1) && !defined(DEBUG_DISABLE_XMAXLIMIT) #if ( (defined(X_MAX_PIN) && (X_MAX_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_XMAXLIMIT)
#ifdef TMC2130_SG_HOMING
// Stall guard homing turned on, now decide if software or hardware one
#ifndef TMC2130_SG_HOMING_SW_XY #ifndef TMC2130_SG_HOMING_SW_XY
x_max_endstop = (READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING); x_max_endstop = (READ(X_TMC2130_DIAG) != X_MAX_ENDSTOP_INVERTING);
#else //TMC2130_SG_HOMING_SW_XY #else //TMC2130_SG_HOMING_SW_XY
x_max_endstop = tmc2130_axis_stalled[X_AXIS]; x_max_endstop = tmc2130_axis_stalled[X_AXIS];
#endif //TMC2130_SG_HOMING_SW_XY #endif //TMC2130_SG_HOMING_SW_XY
#else
// Normal homing
x_max_endstop = (READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
#endif
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){ if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
endstops_trigsteps[X_AXIS] = count_position[X_AXIS]; endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true; endstop_x_hit=true;
@ -480,12 +499,20 @@ void isr() {
#endif #endif
CHECK_ENDSTOPS CHECK_ENDSTOPS
{ {
#if defined(Y_MIN_PIN) && (Y_MIN_PIN > -1) && !defined(DEBUG_DISABLE_YMINLIMIT)
#if ( (defined(Y_MIN_PIN) && (Y_MIN_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_YMINLIMIT)
#ifdef TMC2130_SG_HOMING
// Stall guard homing turned on, now decide if software or hardware one
#ifndef TMC2130_SG_HOMING_SW_XY #ifndef TMC2130_SG_HOMING_SW_XY
y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING); y_min_endstop = (READ(Y_TMC2130_DIAG) != Y_MIN_ENDSTOP_INVERTING);
#else //TMC2130_SG_HOMING_SW_XY #else //TMC2130_SG_HOMING_SW_XY
y_min_endstop = tmc2130_axis_stalled[Y_AXIS]; y_min_endstop = tmc2130_axis_stalled[Y_AXIS];
#endif //TMC2130_SG_HOMING_SW_XY #endif //TMC2130_SG_HOMING_SW_XY
#else
// Normal homing
y_min_endstop = (READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
#endif
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) { if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS]; endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true; endstop_y_hit=true;
@ -498,12 +525,19 @@ void isr() {
else { // +direction else { // +direction
CHECK_ENDSTOPS CHECK_ENDSTOPS
{ {
#if defined(Y_MAX_PIN) && (Y_MAX_PIN > -1) && !defined(DEBUG_DISABLE_YMAXLIMIT) #if ( (defined(Y_MAX_PIN) && (Y_MAX_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_YMAXLIMIT)
#ifdef TMC2130_SG_HOMING
// Stall guard homing turned on, now decide if software or hardware one
#ifndef TMC2130_SG_HOMING_SW_XY #ifndef TMC2130_SG_HOMING_SW_XY
y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING); y_max_endstop = (READ(Y_TMC2130_DIAG) != Y_MAX_ENDSTOP_INVERTING);
#else //TMC2130_SG_HOMING_SW_XY #else //TMC2130_SG_HOMING_SW_XY
y_max_endstop = tmc2130_axis_stalled[Y_AXIS]; y_max_endstop = tmc2130_axis_stalled[Y_AXIS];
#endif //TMC2130_SG_HOMING_SW_XY #endif //TMC2130_SG_HOMING_SW_XY
#else
// Normal homing
y_max_endstop = (READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
#endif
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){ if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS]; endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true; endstop_y_hit=true;
@ -687,6 +721,9 @@ void isr() {
counter_e -= current_block->step_event_count; counter_e -= current_block->step_event_count;
count_position[E_AXIS]+=count_direction[E_AXIS]; count_position[E_AXIS]+=count_direction[E_AXIS];
WRITE_E_STEP(INVERT_E_STEP_PIN); WRITE_E_STEP(INVERT_E_STEP_PIN);
#ifdef PAT9125
fsensor_counter++;
#endif //PAT9125
} }
#endif #endif
@ -770,13 +807,20 @@ void isr() {
if (step_events_completed >= current_block->step_event_count) { if (step_events_completed >= current_block->step_event_count) {
#ifdef PAT9125 #ifdef PAT9125
if (current_block->steps_e < 0) //black magic - decrement filament sensor errors for negative extruder move fsensor_st_block_chunk(current_block, fsensor_counter);
if (fsensor_err_cnt) fsensor_err_cnt--; fsensor_counter = 0;
#endif //PAT9125 #endif //PAT9125
current_block = NULL; current_block = NULL;
plan_discard_current_block(); plan_discard_current_block();
} }
#ifdef PAT9125
else if (fsensor_counter >= fsensor_chunk_len)
{
fsensor_st_block_chunk(current_block, fsensor_counter);
fsensor_counter = 0;
}
#endif //PAT9125
} }
#ifdef TMC2130 #ifdef TMC2130
tmc2130_st_isr(LastStepMask); tmc2130_st_isr(LastStepMask);
@ -805,6 +849,10 @@ void advance_isr() {
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN); WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
e_steps < 0 ? ++e_steps : --e_steps; e_steps < 0 ? ++e_steps : --e_steps;
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN); WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
#ifdef PAT9125
fsensor_counter++;
#endif //PAT9125
} }
} }
} }
@ -929,6 +977,18 @@ void st_init()
//endstops and pullups //endstops and pullups
#ifdef TMC2130_SG_HOMING
SET_INPUT(X_TMC2130_DIAG);
WRITE(X_TMC2130_DIAG,HIGH);
SET_INPUT(Y_TMC2130_DIAG);
WRITE(Y_TMC2130_DIAG,HIGH);
SET_INPUT(Z_TMC2130_DIAG);
WRITE(Z_TMC2130_DIAG,HIGH);
#endif
#if defined(X_MIN_PIN) && X_MIN_PIN > -1 #if defined(X_MIN_PIN) && X_MIN_PIN > -1
SET_INPUT(X_MIN_PIN); SET_INPUT(X_MIN_PIN);
#ifdef ENDSTOPPULLUP_XMIN #ifdef ENDSTOPPULLUP_XMIN

View File

@ -212,8 +212,8 @@ uint8_t tmc2130_sample_diag()
uint8_t mask = 0; uint8_t mask = 0;
if (READ(X_TMC2130_DIAG)) mask |= X_AXIS_MASK; if (READ(X_TMC2130_DIAG)) mask |= X_AXIS_MASK;
if (READ(Y_TMC2130_DIAG)) mask |= Y_AXIS_MASK; if (READ(Y_TMC2130_DIAG)) mask |= Y_AXIS_MASK;
if (READ(Z_TMC2130_DIAG)) mask |= Z_AXIS_MASK; // if (READ(Z_TMC2130_DIAG)) mask |= Z_AXIS_MASK;
if (READ(E0_TMC2130_DIAG)) mask |= E_AXIS_MASK; // if (READ(E0_TMC2130_DIAG)) mask |= E_AXIS_MASK;
return mask; return mask;
} }
@ -222,7 +222,8 @@ void tmc2130_st_isr(uint8_t last_step_mask)
if (tmc2130_mode == TMC2130_MODE_SILENT) return; if (tmc2130_mode == TMC2130_MODE_SILENT) return;
bool crash = false; bool crash = false;
uint8_t diag_mask = tmc2130_sample_diag(); uint8_t diag_mask = tmc2130_sample_diag();
for (uint8_t axis = X_AXIS; axis <= E_AXIS; axis++) // for (uint8_t axis = X_AXIS; axis <= E_AXIS; axis++)
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++)
{ {
uint8_t mask = (X_AXIS_MASK << axis); uint8_t mask = (X_AXIS_MASK << axis);
if (diag_mask & mask) tmc2130_sg_err[axis]++; if (diag_mask & mask) tmc2130_sg_err[axis]++;

View File

@ -189,6 +189,8 @@ static void prusa_stat_temperatures();
static void prusa_stat_printinfo(); static void prusa_stat_printinfo();
static void lcd_farm_no(); static void lcd_farm_no();
static void lcd_menu_extruder_info(); static void lcd_menu_extruder_info();
static void lcd_menu_fails_stats();
#ifdef DOGLCD #ifdef DOGLCD
static void lcd_set_contrast(); static void lcd_set_contrast();
#endif #endif
@ -961,6 +963,47 @@ static void lcd_menu_extruder_info()
} }
} }
static void lcd_menu_fails_stats()
{
// Display screen info
lcd.setCursor(0, 0);
lcd.print("Failure stats ");
// Display power failures
uint8_t power_count = eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT);
lcd.setCursor(0, 1);
lcd.print(" Power failures: ");
lcd.setCursor(17, 1);
lcd.print(itostr3((int)power_count));
// Display Crash detected
uint8_t crash_count = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT);
lcd.setCursor(0, 2);
lcd.print(" Crash detected: ");
lcd.setCursor(17, 2);
lcd.print(itostr3((int)crash_count));
// Display filament failures
uint8_t ferror_count = eeprom_read_byte((uint8_t*)EEPROM_FERROR_COUNT);
lcd.setCursor(0, 3);
lcd.print(" Filament fails: ");
lcd.setCursor(17, 3);
lcd.print(itostr3((int)ferror_count));
if (lcd_clicked())
{
lcd_quick_feedback();
lcd_return_to_status();
}
}
static void lcd_menu_temperatures() static void lcd_menu_temperatures()
{ {
lcd.setCursor(1, 1); lcd.setCursor(1, 1);
@ -1034,13 +1077,15 @@ static void lcd_support_menu()
MENU_ITEM(back, MSG_MAIN, lcd_main_menu); MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM(back, PSTR("Firmware:"), lcd_main_menu);
MENU_ITEM(back, PSTR(" " FW_version_build), lcd_main_menu);
// Ideally this block would be optimized out by the compiler. // Ideally this block would be optimized out by the compiler.
const uint8_t fw_string_len = strlen_P(FW_VERSION_STR_P()); /* const uint8_t fw_string_len = strlen_P(FW_VERSION_STR_P());
if (fw_string_len < 6) { if (fw_string_len < 6) {
MENU_ITEM(back, PSTR(MSG_FW_VERSION " - " FW_version), lcd_main_menu); MENU_ITEM(back, PSTR(MSG_FW_VERSION " - " FW_version), lcd_main_menu);
} else { } else {
MENU_ITEM(back, PSTR("FW - " FW_version), lcd_main_menu); MENU_ITEM(back, PSTR("FW - " FW_version), lcd_main_menu);
} }*/
MENU_ITEM(back, MSG_PRUSA3D, lcd_main_menu); MENU_ITEM(back, MSG_PRUSA3D, lcd_main_menu);
MENU_ITEM(back, MSG_PRUSA3D_FORUM, lcd_main_menu); MENU_ITEM(back, MSG_PRUSA3D_FORUM, lcd_main_menu);
@ -1066,6 +1111,8 @@ static void lcd_support_menu()
MENU_ITEM(function, PSTR("XYZ cal. details"), lcd_service_mode_show_result); MENU_ITEM(function, PSTR("XYZ cal. details"), lcd_service_mode_show_result);
} }
MENU_ITEM(submenu, MSG_INFO_EXTRUDER, lcd_menu_extruder_info); MENU_ITEM(submenu, MSG_INFO_EXTRUDER, lcd_menu_extruder_info);
MENU_ITEM(submenu, PSTR("Temperatures"), lcd_menu_temperatures); MENU_ITEM(submenu, PSTR("Temperatures"), lcd_menu_temperatures);
if (fans_check_enabled == true) { if (fans_check_enabled == true) {
MENU_ITEM(function, PSTR("Check fans [EN]"), lcd_set_fan_check); MENU_ITEM(function, PSTR("Check fans [EN]"), lcd_set_fan_check);
@ -1074,6 +1121,10 @@ static void lcd_support_menu()
MENU_ITEM(function, PSTR("Check fans [DIS]"), lcd_set_fan_check); MENU_ITEM(function, PSTR("Check fans [DIS]"), lcd_set_fan_check);
} }
#endif //MK1BP #endif //MK1BP
#ifdef AUTOMATIC_RECOVERY_AFTER_CRASH
MENU_ITEM(back, PSTR("Auto recover crash"), lcd_main_menu);
#endif
END_MENU(); END_MENU();
} }
@ -4013,6 +4064,9 @@ static void lcd_main_menu()
MENU_ITEM(submenu, MSG_STATISTICS, lcd_menu_statistics); MENU_ITEM(submenu, MSG_STATISTICS, lcd_menu_statistics);
} }
MENU_ITEM(submenu, MSG_SUPPORT, lcd_support_menu); MENU_ITEM(submenu, MSG_SUPPORT, lcd_support_menu);
MENU_ITEM(submenu, PSTR("Fail stats"), lcd_menu_fails_stats);
END_MENU(); END_MENU();
} }

View File

@ -32,7 +32,7 @@
// Steps per unit {X,Y,Z,E} // Steps per unit {X,Y,Z,E}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140} //#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280} //Extruder motor changed back to 200step type #define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
// Endstop inverting // Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop. const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
@ -77,8 +77,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define Z_AXIS_ALWAYS_ON 1 #define Z_AXIS_ALWAYS_ON 1
//DEBUG //DEBUG
#if 0
#define DEBUG_DCODES //D codes #define DEBUG_DCODES //D codes
#if 0
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored #define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored #define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored #define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
@ -104,7 +104,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes #define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis #define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis (increased from 16 to 32) #define TMC2130_USTEPS_E 32 // microstep resolution for E axis
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes #define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis #define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis #define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
@ -115,7 +115,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_PWM_FREQ_X 2 // PWMCONF #define TMC2130_PWM_FREQ_X 2 // PWMCONF
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF #define TMC2130_PWM_GRAD_Y 4 // PWMCONF
#define TMC2130_PWM_AMPL_Y 210 // PWMCONF #define TMC2130_PWM_AMPL_Y 215 // PWMCONF
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF #define TMC2130_PWM_AUTO_Y 1 // PWMCONF
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF #define TMC2130_PWM_FREQ_Y 2 // PWMCONF
@ -137,19 +137,19 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode #define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
#define TMC2130_THIGH 0 // THIGH - unused #define TMC2130_THIGH 0 // THIGH - unused
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold #define TMC2130_TCOOLTHRS 500 // TCOOLTHRS - coolstep treshold
#define TMC2130_SG_HOMING 1 // stallguard homing #define TMC2130_SG_HOMING 1 // stallguard homing
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes //#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis #define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
#define TMC2130_SG_THRS_X 0 // stallguard sensitivity for X axis #define TMC2130_SG_THRS_X 6 // stallguard sensitivity for X axis
#define TMC2130_SG_THRS_Y 0 // stallguard sensitivity for Y axis #define TMC2130_SG_THRS_Y 6 // stallguard sensitivity for Y axis
#define TMC2130_SG_THRS_Z 2 // stallguard sensitivity for Z axis #define TMC2130_SG_THRS_Z 3 // stallguard sensitivity for Z axis
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing) #define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only) //new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes #define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
#define TMC2130_CURRENTS_R {13, 18, 20, 22} // default running currents for all axes #define TMC2130_CURRENTS_R {13, 31, 20, 22} // default running currents for all axes
//#define TMC2130_DEBUG //#define TMC2130_DEBUG
//#define TMC2130_DEBUG_WR //#define TMC2130_DEBUG_WR
@ -472,7 +472,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DEFAULT_PID_TEMP 210 #define DEFAULT_PID_TEMP 210
#define MIN_PRINT_FAN_SPEED 50 #define MIN_PRINT_FAN_SPEED 75
#ifdef SNMM #ifdef SNMM
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print #define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
@ -480,6 +480,14 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print #define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
#endif #endif
#define UVLO_Z_AXIS_SHIFT 2 // How much shall the print head be lifted on power panic?
// Ideally the Z axis will reach a zero phase of the stepper driver on power outage. To simplify this,
// UVLO_Z_AXIS_SHIFT shall be an integer multiply of the stepper driver cycle, that is 4x full step.
// For example, the Prusa i3 MK2 with 16 microsteps per full step has Z stepping of 400 microsteps per mm.
// At 400 microsteps per mm, a full step lifts the Z axis by 0.04mm, and a stepper driver cycle is 0.16mm.
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
#define UVLO_Z_AXIS_SHIFT 1.92
#define HEATBED_V2
#endif //__CONFIGURATION_PRUSA_H #endif //__CONFIGURATION_PRUSA_H