Merge branch 'MK3' into MK3_NEW_SD_COMPILATION

This commit is contained in:
Alex Voinea 2020-03-03 14:14:43 +02:00
commit 53e130fc6d
No known key found for this signature in database
GPG Key ID: F5034E7CFCF2F973
42 changed files with 3291 additions and 1887 deletions

View File

@ -16,8 +16,8 @@ extern uint16_t nPrinterType;
extern PGM_P sPrinterName;
// Firmware version
#define FW_VERSION "3.8.1"
#define FW_COMMIT_NR 2869
#define FW_VERSION "3.9.0-RC1"
#define FW_COMMIT_NR 3272
// FW_VERSION_UNKNOWN means this is an unofficial build.
// The firmware should only be checked into github with this symbol.
#define FW_DEV_VERSION FW_VERSION_UNKNOWN
@ -424,7 +424,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
#define DEFAULT_XJERK 10 // (mm/sec)
#define DEFAULT_YJERK 10 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 2.5 // (mm/sec)
#define DEFAULT_EJERK 4.5 // (mm/sec)
//===========================================================================
//=============================Additional Features===========================

View File

@ -165,8 +165,8 @@ void Config_PrintSettings(uint8_t level)
#endif
if (level >= 10) {
#ifdef LIN_ADVANCE
printf_P(PSTR("%SLinear advance settings:\n M900 K%.2f E/D = %.2f\n"),
echomagic, extruder_advance_k, advance_ed_ratio);
printf_P(PSTR("%SLinear advance settings:%S M900 K%.2f\n"),
echomagic, echomagic, extruder_advance_K);
#endif //LIN_ADVANCE
}
}

View File

@ -270,43 +270,29 @@
#endif
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*/
* Linear Pressure Control v1.5
*
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
*
* NOTE: K values for LIN_ADVANCE 1.5 differs from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
#define LIN_ADVANCE
#ifdef LIN_ADVANCE
#define LIN_ADVANCE_K 0 //Try around 45 for PLA, around 25 for ABS.
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Prusa Slic3r) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0 // Unit: mm compression per 1mm/s extruder speed
//#define LA_NOCOMPAT // Disable Linear Advance 1.0 compatibility
//#define LA_LIVE_K // Allow adjusting K in the Tune menu
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
//#define LA_DEBUG_LOGIC // @wavexx: setup logic channels for isr debugging
#endif
// Arc interpretation settings:

View File

@ -99,6 +99,18 @@ void print_mem(uint32_t address, uint16_t count, uint8_t type, uint8_t countperl
#ifdef DEBUG_DCODE3
#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>
This command can be used without any additional parameters. It will read the entire eeprom.
D3 [ A | C | X ]
- `A` - Address (0x0000-0x0fff)
- `C` - Count (0x0001-0x1000)
- `X` - Data
*
*/
void dcode_3()
{
DBG(_N("D3 - Read/Write EEPROM\n"));
@ -176,6 +188,14 @@ extern float axis_steps_per_unit[NUM_AXIS];
#endif //0
#define LOG(args...)
/*!
*
### D-1 - Endless Loop <a href="https://reprap.org/wiki/G-code#G28:_Move_to_Origin_.28Home.29">D-1: Endless Loop</a>
D-1
*
*/
void dcode__1()
{
printf_P(PSTR("D-1 - Endless loop\n"));
@ -185,6 +205,15 @@ void dcode__1()
#ifdef DEBUG_DCODES
/*!
*
### D0 - Reset <a href="https://reprap.org/wiki/G-code#D0:_Reset">D0: Reset</a>
D0 [ B ]
- `B` - Bootloader
*
*/
void dcode_0()
{
if (*(strchr_pointer + 1) == 0) return;
@ -203,6 +232,14 @@ void dcode_0()
}
}
/*!
*
### D1 - Clear EEPROM and RESET <a href="https://reprap.org/wiki/G-code#D1:_Clear_EEPROM_and_RESET">D1: Clear EEPROM and RESET</a>
D1
*
*/
void dcode_1()
{
LOG("D1 - Clear EEPROM and RESET\n");
@ -213,6 +250,18 @@ void dcode_1()
while(1);
}
/*!
*
### D2 - Read/Write RAM <a href="https://reprap.org/wiki/G-code#D2:_Read.2FWrite_RAM">D2: Read/Write RAM</a>
This command can be used without any additional parameters. It will read the entire RAM.
D2 [ A | C | X ]
- `A` - Address (0x0000-0x1fff)
- `C` - Count (0x0001-0x2000)
- `X` - Data
*
*/
void dcode_2()
{
LOG("D2 - Read/Write RAM\n");
@ -256,6 +305,19 @@ void dcode_2()
}*/
}
/*!
*
### D4 - Read/Write PIN <a href="https://reprap.org/wiki/G-code#D4:_Read.2FWrite_PIN">D4: Read/Write PIN</a>
To read the digital value of a pin you need only to define the pin number.
D4 [ P | F | V ]
- `P` - Pin (0-255)
- `F` - Function in/out (0/1)
- `V` - Value (0/1)
*
*/
void dcode_4()
{
LOG("D4 - Read/Write PIN\n");
@ -288,6 +350,19 @@ void dcode_4()
#ifdef DEBUG_DCODE5
/*!
*
### D5 - Read/Write FLASH <a href="https://reprap.org/wiki/G-code#D5:_Read.2FWrite_FLASH">D5: Read/Write Flash</a>
This command can be used without any additional parameters. It will read the 1kb FLASH.
D5 [ A | C | X | E ]
- `A` - Address (0x00000-0x3ffff)
- `C` - Count (0x0001-0x2000)
- `X` - Data
- `E` - Erase
*
*/
void dcode_5()
{
printf_P(PSTR("D5 - Read/Write FLASH\n"));
@ -351,11 +426,25 @@ void dcode_5()
#ifdef DEBUG_DCODES
/*!
*
### D6 - Read/Write external FLASH <a href="https://reprap.org/wiki/G-code#D6:_Read.2FWrite_external_FLASH">D6: Read/Write external Flash</a>
Reserved
*
*/
void dcode_6()
{
LOG("D6 - Read/Write external FLASH\n");
}
/*!
*
### D7 - Read/Write Bootloader <a href="https://reprap.org/wiki/G-code#D7:_Read.2FWrite_Bootloader">D7: Read/Write Bootloader</a>
Reserved
*
*/
void dcode_7()
{
LOG("D7 - Read/Write Bootloader\n");
@ -371,6 +460,18 @@ void dcode_7()
*/
}
/*!
*
### D8 - Read/Write PINDA <a href="https://reprap.org/wiki/G-code#D8:_Read.2FWrite_PINDA">D8: Read/Write PINDA</a>
D8 [ ? | ! | P | Z ]
- `?` - Read PINDA temperature shift values
- `!` - Reset PINDA temperature shift values to default
- `P` - Pinda temperature [C]
- `Z` - Z Offset [mm]
*
*/
void dcode_8()
{
printf_P(PSTR("D8 - Read/Write PINDA\n"));
@ -412,6 +513,23 @@ void dcode_8()
printf_P(PSTR("temp_pinda=%d offset_z=%d.%03d\n"), (int)temp_pinda, (int)offset_z, ((int)(1000 * offset_z) % 1000));
}
/*!
*
### D9 - Read ADC <a href="https://reprap.org/wiki/G-code#D9:_Read.2FWrite_ADC">D9: Read ADC</a>
D9 [ I | V ]
- `I` - ADC channel index
- `0` - Heater 0 temperature
- `1` - Heater 1 temperature
- `2` - Bed temperature
- `3` - PINDA temperature
- `4` - PWR voltage
- `5` - Ambient temperature
- `6` - BED voltage
- `V` Value to be written as simulated
*
*/
const char* dcode_9_ADC_name(uint8_t i)
{
switch (i)
@ -485,12 +603,24 @@ void dcode_9()
}
}
/*!
*
### D10 - Set XYZ calibration = OK <a href="https://reprap.org/wiki/G-code#D10:_Set_XYZ_calibration_.3D_OK">D10: Set XYZ calibration = OK</a>
*
*/
void dcode_10()
{//Tell the printer that XYZ calibration went OK
LOG("D10 - XYZ calibration = OK\n");
calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST);
}
/*!
*
### D12 - Time <a href="https://reprap.org/wiki/G-code#D12:_Time">D12: Time</a>
*
*/
void dcode_12()
{//Time
LOG("D12 - Time\n");
@ -636,6 +766,20 @@ void dcode_2130()
#endif //TMC2130
#ifdef PAT9125
/*!
*
### D9125 - PAT9125 filament sensor <a href="https://reprap.org/wiki/G-code#D9:_Read.2FWrite_ADC">D9125: PAT9125 filament sensor</a>
D9125 [ ? | ! | R | X | Y | L ]
- `?` - Print values
- `!` - Print values
- `R` - Resolution. Not active in code
- `X` - X values
- `Y` - Y values
- `L` - Activate filament sensor log
*
*/
void dcode_9125()
{
LOG("D9125 - PAT9125\n");

View File

@ -146,40 +146,39 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
#if defined(Z_AXIS_ALWAYS_ON)
#ifdef Z_DUAL_STEPPER_DRIVERS
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#define poweron_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
#define poweroff_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#else
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
#define disable_z() {}
#define poweron_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
#define poweroff_z() {}
#endif
#else
#ifdef Z_DUAL_STEPPER_DRIVERS
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#define poweron_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
#define poweroff_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#else
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#define poweron_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
#define poweroff_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#endif
#endif
#else
#define enable_z() {}
#define disable_z() {}
#define poweron_z() {}
#define poweroff_z() {}
#endif
#ifdef PSU_Delta
#ifndef PSU_Delta
#define enable_z() poweron_z()
#define disable_z() poweroff_z()
#else
void init_force_z();
void check_force_z();
#undef disable_z
#define disable_z() disable_force_z()
void disable_force_z();
#undef enable_z
#define enable_z() enable_force_z()
void enable_force_z();
void disable_force_z();
#define enable_z() enable_force_z()
#define disable_z() disable_force_z()
#endif // PSU_Delta
//#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
//#ifdef Z_DUAL_STEPPER_DRIVERS
//#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
@ -308,6 +307,7 @@ extern float max_pos[3];
extern bool axis_known_position[3];
extern int fanSpeed;
extern int8_t lcd_change_fil_state;
extern float default_retraction;
#ifdef TMC2130
void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0);
@ -444,9 +444,8 @@ void setup_uvlo_interrupt();
void setup_fan_interrupt();
#endif
//extern void recover_machine_state_after_power_panic();
extern void recover_machine_state_after_power_panic(bool bTiny);
extern void restore_print_from_eeprom();
extern bool recover_machine_state_after_power_panic();
extern void restore_print_from_eeprom(bool mbl_was_active);
extern void position_menu();
extern void print_world_coordinates();

File diff suppressed because it is too large Load Diff

View File

@ -34,7 +34,8 @@
//#define PAT9125_I2C_ADDR 0x79 //ID=HI
//#define PAT9125_I2C_ADDR 0x73 //ID=NC
#define PAT9125_XRES 0
#define PAT9125_YRES 240
#define PAT9125_YRES 240 // maximum resolution (5*X cpi)
#define PAT9124_YRES_MM (5*PAT9125_YRES/25.4) // counts per mm
//SM4 configuration
#define SM4_DEFDELAY 500 //default step delay [us]

View File

@ -72,14 +72,14 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
#define EEPROM_FILENAME (EEPROM_UVLO_CURRENT_POSITION - 8) //8chars to store filename without extension
#define EEPROM_FILE_POSITION (EEPROM_FILENAME - 4) //32 bit for uint32_t file position
#define EEPROM_UVLO_CURRENT_POSITION_Z (EEPROM_FILE_POSITION - 4) //float for current position in Z
#define EEPROM_UVLO_TARGET_HOTEND (EEPROM_UVLO_CURRENT_POSITION_Z - 1)
#define EEPROM_UVLO_TARGET_BED (EEPROM_UVLO_TARGET_HOTEND - 1)
#define EEPROM_UVLO_UNUSED_001 (EEPROM_UVLO_CURRENT_POSITION_Z - 1) // uint8_t (unused)
#define EEPROM_UVLO_TARGET_BED (EEPROM_UVLO_UNUSED_001 - 1)
#define EEPROM_UVLO_FEEDRATE (EEPROM_UVLO_TARGET_BED - 2) //uint16_t
#define EEPROM_UVLO_FAN_SPEED (EEPROM_UVLO_FEEDRATE - 1)
#define EEPROM_FAN_CHECK_ENABLED (EEPROM_UVLO_FAN_SPEED - 1)
#define EEPROM_UVLO_MESH_BED_LEVELING (EEPROM_FAN_CHECK_ENABLED - 9*2)
#define EEPROM_UVLO_Z_MICROSTEPS (EEPROM_UVLO_MESH_BED_LEVELING - 2)
#define EEPROM_UVLO_Z_MICROSTEPS (EEPROM_UVLO_MESH_BED_LEVELING - 2) // uint16_t (could be removed)
#define EEPROM_UVLO_E_ABS (EEPROM_UVLO_Z_MICROSTEPS - 1)
#define EEPROM_UVLO_CURRENT_POSITION_E (EEPROM_UVLO_E_ABS - 4) //float for current position in E
@ -165,13 +165,11 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
#define EEPROM_EXTRUDER_MULTIPLIER_2 (EEPROM_EXTRUDER_MULTIPLIER_1 - 4) //float
#define EEPROM_EXTRUDEMULTIPLY (EEPROM_EXTRUDER_MULTIPLIER_2 - 2) // uint16
//
#define EEPROM_UVLO_TINY_CURRENT_POSITION_Z (EEPROM_EXTRUDEMULTIPLY-4) // float
#define EEPROM_UVLO_TINY_Z_MICROSTEPS (EEPROM_UVLO_TINY_CURRENT_POSITION_Z-2) // uint16
#define EEPROM_UVLO_TARGET_HOTEND (EEPROM_UVLO_TINY_CURRENT_POSITION_Z-2) // uint16
// Sound Mode
//#define EEPROM_SOUND_MODE (EEPROM_EXTRUDEMULTIPLY-1) // uint8
#define EEPROM_SOUND_MODE (EEPROM_UVLO_TINY_Z_MICROSTEPS-1) // uint8
#define EEPROM_SOUND_MODE (EEPROM_UVLO_TARGET_HOTEND-1) // uint8
#define EEPROM_AUTO_DEPLETE (EEPROM_SOUND_MODE-1) //bool
#define EEPROM_FSENS_OQ_MEASS_ENABLED (EEPROM_AUTO_DEPLETE - 1) //bool
@ -212,9 +210,10 @@ static Sheets * const EEPROM_Sheets_base = (Sheets*)(EEPROM_SHEETS_BASE);
#define EEPROM_BACKLIGHT_MODE (EEPROM_BACKLIGHT_LEVEL_LOW-1) // uint8
#define EEPROM_BACKLIGHT_TIMEOUT (EEPROM_BACKLIGHT_MODE-2) // uint16
#define EEPROM_UVLO_LA_K (EEPROM_BACKLIGHT_TIMEOUT-4) // float
//This is supposed to point to last item to allow EEPROM overrun check. Please update when adding new items.
#define EEPROM_LAST_ITEM EEPROM_BACKLIGHT_TIMEOUT
#define EEPROM_LAST_ITEM EEPROM_UVLO_LA_K
// !!!!!
// !!!!! this is end of EEPROM section ... all updates MUST BE inserted before this mark !!!!!
// !!!!!

View File

@ -6,12 +6,9 @@
#include <avr/pgmspace.h>
#include "pat9125.h"
#include "stepper.h"
#include "planner.h"
#include "fastio.h"
#include "io_atmega2560.h"
#include "cmdqueue.h"
#include "ultralcd.h"
#include "ConfigurationStore.h"
#include "mmu.h"
#include "cardreader.h"
@ -21,19 +18,19 @@
//! @name Basic parameters
//! @{
#define FSENSOR_CHUNK_LEN 0.64F //!< filament sensor chunk length 0.64mm
#define FSENSOR_ERR_MAX 17 //!< filament sensor maximum error count for runout detection
#define FSENSOR_CHUNK_LEN 1.25 //!< filament sensor chunk length (mm)
#define FSENSOR_ERR_MAX 4 //!< filament sensor maximum error/chunk count for runout detection
#define FSENSOR_SOFTERR_CMAX 3 //!< number of contiguous soft failures before a triggering a runout
#define FSENSOR_SOFTERR_DELTA 30000 //!< maximum interval (ms) to consider soft failures contiguous
//! @}
//! @name Optical quality measurement parameters
//! @{
#define FSENSOR_OQ_MAX_ES 6 //!< maximum error sum while loading (length ~64mm = 100chunks)
#define FSENSOR_OQ_MAX_EM 2 //!< maximum error counter value while loading
#define FSENSOR_OQ_MIN_YD 2 //!< minimum yd per chunk (applied to avg value)
#define FSENSOR_OQ_MAX_YD 200 //!< maximum yd per chunk (applied to avg value)
#define FSENSOR_OQ_MAX_PD 4 //!< maximum positive deviation (= yd_max/yd_avg)
#define FSENSOR_OQ_MAX_ND 5 //!< maximum negative deviation (= yd_avg/yd_min)
#define FSENSOR_OQ_MAX_SH 13 //!< maximum shutter value
#define FSENSOR_OQ_MAX_ES 2 //!< maximum sum of error blocks during filament recheck
#define FSENSOR_OQ_MIN_YD 2 //!< minimum yd sum during filament check (counts per inch)
#define FSENSOR_OQ_MIN_BR 80 //!< minimum brightness value
#define FSENSOR_OQ_MAX_SH 10 //!< maximum shutter value
//! @}
const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n";
@ -47,25 +44,30 @@ const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n";
#define FSENSOR_INT_PIN_PCMSK_BIT PCINT13 // PinChange Interrupt / PinChange Enable Mask @ PJ4
#define FSENSOR_INT_PIN_PCICR_BIT PCIE1 // PinChange Interrupt Enable / Flag @ PJ4
//uint8_t fsensor_int_pin = FSENSOR_INT_PIN;
uint8_t fsensor_int_pin_old = 0;
int16_t fsensor_chunk_len = 0;
//! enabled = initialized and sampled every chunk event
bool fsensor_enabled = true;
//! runout watching is done in fsensor_update (called from main loop)
bool fsensor_watch_runout = true;
//! not responding - is set if any communication error occurred during initialization or readout
bool fsensor_not_responding = false;
#ifdef PAT9125
uint8_t fsensor_int_pin_old = 0;
//! optical checking "chunk lenght" (already in steps)
int16_t fsensor_chunk_len = 0;
//! enable/disable quality meassurement
bool fsensor_oq_meassure_enabled = false;
//! number of errors, updated in ISR
uint8_t fsensor_err_cnt = 0;
//! variable for accumulating step count (updated callbacks from stepper and ISR)
int16_t fsensor_st_cnt = 0;
//! last dy value from pat9125 sensor (used in ISR)
int16_t fsensor_dy_old = 0;
//! count of total sensor "soft" failures (filament status checks)
uint8_t fsensor_softfail = 0;
//! timestamp of last soft failure
unsigned long fsensor_softfail_last = 0;
//! count of soft failures within the configured time
uint8_t fsensor_softfail_ccnt = 0;
#endif
//! log flag: 0=log disabled, 1=log enabled
uint8_t fsensor_log = 1;
@ -78,6 +80,8 @@ uint8_t fsensor_log = 1;
bool fsensor_autoload_enabled = true;
//! autoload watching enable/disable flag
bool fsensor_watch_autoload = false;
#ifdef PAT9125
//
uint16_t fsensor_autoload_y;
//
@ -87,6 +91,7 @@ uint32_t fsensor_autoload_last_millis;
//
uint8_t fsensor_autoload_sum;
//! @}
#endif
//! @name filament optical quality measurement variables
@ -124,14 +129,34 @@ unsigned long nIRsensorLastTime;
void fsensor_stop_and_save_print(void)
{
printf_P(PSTR("fsensor_stop_and_save_print\n"));
stop_and_save_print_to_ram(0, 0); //XYZE - no change
stop_and_save_print_to_ram(0, 0);
fsensor_watch_runout = false;
}
#ifdef PAT9125
// Reset all internal counters to zero, including stepper callbacks
void fsensor_reset_err_cnt()
{
fsensor_err_cnt = 0;
pat9125_y = 0;
st_reset_fsensor();
}
void fsensor_set_axis_steps_per_unit(float u)
{
fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * u);
}
#endif
void fsensor_restore_print_and_continue(void)
{
printf_P(PSTR("fsensor_restore_print_and_continue\n"));
fsensor_err_cnt = 0;
restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change
fsensor_watch_runout = true;
#ifdef PAT9125
fsensor_reset_err_cnt();
#endif
restore_print_from_ram_and_continue(0);
}
// fsensor_checkpoint_print cuts the current print job at the current position,
@ -155,7 +180,7 @@ void fsensor_init(void)
#ifdef PAT9125
uint8_t oq_meassure_enabled = eeprom_read_byte((uint8_t*)EEPROM_FSENS_OQ_MEASS_ENABLED);
fsensor_oq_meassure_enabled = (oq_meassure_enabled == 1)?true:false;
fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * cs.axis_steps_per_unit[E_AXIS]);
fsensor_set_axis_steps_per_unit(cs.axis_steps_per_unit[E_AXIS]);
if (!pat9125)
{
@ -195,8 +220,7 @@ bool fsensor_enable(bool bUpdateEEPROM)
fsensor_enabled = pat9125 ? true : false;
fsensor_watch_runout = true;
fsensor_oq_meassure = false;
fsensor_err_cnt = 0;
fsensor_dy_old = 0;
fsensor_reset_err_cnt();
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, fsensor_enabled ? 0x01 : 0x00);
FSensorStateMenu = fsensor_enabled ? 1 : 0;
}
@ -261,7 +285,7 @@ void fsensor_autoload_check_start(void)
if (!fsensor_enabled) return;
if (!fsensor_autoload_enabled) return;
if (fsensor_watch_autoload) return;
if (!pat9125_update_y()) //update sensor
if (!pat9125_update()) //update sensor
{
fsensor_disable();
fsensor_not_responding = true;
@ -276,12 +300,11 @@ void fsensor_autoload_check_start(void)
fsensor_autoload_last_millis = _millis();
fsensor_watch_runout = false;
fsensor_watch_autoload = true;
fsensor_err_cnt = 0;
}
void fsensor_autoload_check_stop(void)
{
// puts_P(_N("fsensor_autoload_check_stop\n"));
if (!fsensor_enabled) return;
// puts_P(_N("fsensor_autoload_check_stop 1\n"));
@ -292,7 +315,7 @@ void fsensor_autoload_check_stop(void)
fsensor_autoload_sum = 0;
fsensor_watch_autoload = false;
fsensor_watch_runout = true;
fsensor_err_cnt = 0;
fsensor_reset_err_cnt();
}
#endif //PAT9125
@ -357,6 +380,7 @@ bool fsensor_check_autoload(void)
return false;
}
#ifdef PAT9125
void fsensor_oq_meassure_set(bool State)
{
fsensor_oq_meassure_enabled = State;
@ -374,12 +398,11 @@ void fsensor_oq_meassure_start(uint8_t skip)
fsensor_oq_yd_sum = 0;
fsensor_oq_er_sum = 0;
fsensor_oq_er_max = 0;
fsensor_oq_yd_min = FSENSOR_OQ_MAX_YD;
fsensor_oq_yd_min = INT16_MAX;
fsensor_oq_yd_max = 0;
fsensor_oq_sh_sum = 0;
pat9125_update();
pat9125_y = 0;
fsensor_watch_runout = false;
fsensor_oq_meassure = true;
}
@ -391,10 +414,9 @@ void fsensor_oq_meassure_stop(void)
printf_P(_N(" st_sum=%u yd_sum=%u er_sum=%u er_max=%hhu\n"), fsensor_oq_st_sum, fsensor_oq_yd_sum, fsensor_oq_er_sum, fsensor_oq_er_max);
printf_P(_N(" yd_min=%u yd_max=%u yd_avg=%u sh_avg=%u\n"), fsensor_oq_yd_min, fsensor_oq_yd_max, (uint16_t)((uint32_t)fsensor_oq_yd_sum * fsensor_chunk_len / fsensor_oq_st_sum), (uint16_t)(fsensor_oq_sh_sum / fsensor_oq_samples));
fsensor_oq_meassure = false;
fsensor_watch_runout = true;
fsensor_err_cnt = 0;
}
#ifdef FSENSOR_QUALITY
const char _OK[] PROGMEM = "OK";
const char _NG[] PROGMEM = "NG!";
@ -430,18 +452,24 @@ bool fsensor_oq_result(void)
printf_P(_N("fsensor_oq_result %S\n"), (res?_OK:_NG));
return res;
}
#ifdef PAT9125
#endif //FSENSOR_QUALITY
ISR(FSENSOR_INT_PIN_VECT)
{
if (mmu_enabled || ir_sensor_detected) return;
if (!((fsensor_int_pin_old ^ FSENSOR_INT_PIN_PIN_REG) & FSENSOR_INT_PIN_MASK)) return;
fsensor_int_pin_old = FSENSOR_INT_PIN_PIN_REG;
// prevent isr re-entry
static bool _lock = false;
if (_lock) return;
_lock = true;
// fetch fsensor_st_cnt atomically
int st_cnt = fsensor_st_cnt;
fsensor_st_cnt = 0;
sei();
uint8_t old_err_cnt = fsensor_err_cnt;
uint8_t pat9125_res = fsensor_oq_meassure?pat9125_update():pat9125_update_y();
if (!pat9125_res)
@ -450,56 +478,71 @@ ISR(FSENSOR_INT_PIN_VECT)
fsensor_not_responding = true;
printf_P(ERRMSG_PAT9125_NOT_RESP, 1);
}
if (st_cnt != 0)
{ //movement
if (st_cnt > 0) //positive movement
{
if (pat9125_y < 0)
{
if (fsensor_err_cnt)
fsensor_err_cnt += 2;
else
fsensor_err_cnt++;
}
else if (pat9125_y > 0)
{
if (fsensor_err_cnt)
fsensor_err_cnt--;
}
else //(pat9125_y == 0)
if (((fsensor_dy_old <= 0) || (fsensor_err_cnt)) && (st_cnt > (fsensor_chunk_len >> 1)))
fsensor_err_cnt++;
if (fsensor_oq_meassure)
{
if (fsensor_oq_skipchunk)
{
fsensor_oq_skipchunk--;
fsensor_err_cnt = 0;
}
else
{
if (st_cnt == fsensor_chunk_len)
{
if (pat9125_y > 0) if (fsensor_oq_yd_min > pat9125_y) fsensor_oq_yd_min = (fsensor_oq_yd_min + pat9125_y) / 2;
if (pat9125_y >= 0) if (fsensor_oq_yd_max < pat9125_y) fsensor_oq_yd_max = (fsensor_oq_yd_max + pat9125_y) / 2;
}
fsensor_oq_samples++;
fsensor_oq_st_sum += st_cnt;
if (pat9125_y > 0) fsensor_oq_yd_sum += pat9125_y;
if (fsensor_err_cnt > old_err_cnt)
fsensor_oq_er_sum += (fsensor_err_cnt - old_err_cnt);
if (fsensor_oq_er_max < fsensor_err_cnt)
fsensor_oq_er_max = fsensor_err_cnt;
fsensor_oq_sh_sum += pat9125_s;
}
}
}
else //negative movement
{
}
}
else
{ //no movement
{
// movement was planned, check for sensor movement
int8_t st_dir = st_cnt >= 0;
int8_t pat9125_dir = pat9125_y >= 0;
if (pat9125_y == 0)
{
if (st_dir)
{
// no movement detected: we might be within a blind sensor range,
// update the frame and shutter parameters we didn't earlier
if (!fsensor_oq_meassure)
pat9125_update_bs();
// increment the error count only if underexposed: filament likely missing
if ((pat9125_b < FSENSOR_OQ_MIN_BR) && (pat9125_s > FSENSOR_OQ_MAX_SH))
{
// check for a dark frame (<30% avg brightness) with long exposure
++fsensor_err_cnt;
}
else
{
// good frame, filament likely present
if(fsensor_err_cnt) --fsensor_err_cnt;
}
}
}
else if (pat9125_dir != st_dir)
{
// detected direction opposite of motor movement
if (st_dir) ++fsensor_err_cnt;
}
else if (pat9125_dir == st_dir)
{
// direction agreeing with planned movement
if (fsensor_err_cnt) --fsensor_err_cnt;
}
if (st_dir && fsensor_oq_meassure)
{
// extruding with quality assessment
if (fsensor_oq_skipchunk)
{
fsensor_oq_skipchunk--;
fsensor_err_cnt = 0;
}
else
{
if (st_cnt == fsensor_chunk_len)
{
if (pat9125_y > 0) if (fsensor_oq_yd_min > pat9125_y) fsensor_oq_yd_min = (fsensor_oq_yd_min + pat9125_y) / 2;
if (pat9125_y >= 0) if (fsensor_oq_yd_max < pat9125_y) fsensor_oq_yd_max = (fsensor_oq_yd_max + pat9125_y) / 2;
}
fsensor_oq_samples++;
fsensor_oq_st_sum += st_cnt;
if (pat9125_y > 0) fsensor_oq_yd_sum += pat9125_y;
if (fsensor_err_cnt > old_err_cnt)
fsensor_oq_er_sum += (fsensor_err_cnt - old_err_cnt);
if (fsensor_oq_er_max < fsensor_err_cnt)
fsensor_oq_er_max = fsensor_err_cnt;
fsensor_oq_sh_sum += pat9125_s;
}
}
}
#ifdef DEBUG_FSENSOR_LOG
@ -510,9 +553,7 @@ ISR(FSENSOR_INT_PIN_VECT)
}
#endif //DEBUG_FSENSOR_LOG
fsensor_dy_old = pat9125_y;
pat9125_y = 0;
_lock = false;
return;
}
@ -532,32 +573,17 @@ void fsensor_setup_interrupt(void)
PCICR |= bit(FSENSOR_INT_PIN_PCICR_BIT); // enable corresponding PinChangeInterrupt (set of pins)
}
void fsensor_st_block_chunk(int cnt)
{
if (!fsensor_enabled) return;
fsensor_st_cnt += cnt;
// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);}
else {PIN_VAL(FSENSOR_INT_PIN, HIGH);}
}
#endif //PAT9125
void fsensor_st_block_begin(block_t* bl)
{
if (!fsensor_enabled) return;
if (((fsensor_st_cnt > 0) && (bl->direction_bits & 0x8)) ||
((fsensor_st_cnt < 0) && !(bl->direction_bits & 0x8)))
{
// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);}
else {PIN_VAL(FSENSOR_INT_PIN, HIGH);}
}
}
void fsensor_st_block_chunk(block_t* bl, int cnt)
{
if (!fsensor_enabled) return;
fsensor_st_cnt += (bl->direction_bits & 0x8)?-cnt:cnt;
if ((fsensor_st_cnt >= fsensor_chunk_len) || (fsensor_st_cnt <= -fsensor_chunk_len))
{
// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);}
else {PIN_VAL(FSENSOR_INT_PIN, HIGH);}
}
}
//! Common code for enqueing M600 and supplemental codes into the command queue.
//! Used both for the IR sensor and the PAT9125
@ -576,50 +602,61 @@ void fsensor_enque_M600(){
void fsensor_update(void)
{
#ifdef PAT9125
if (fsensor_enabled && fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX))
if (fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX))
{
fsensor_stop_and_save_print();
KEEPALIVE_STATE(IN_HANDLER);
bool autoload_enabled_tmp = fsensor_autoload_enabled;
fsensor_autoload_enabled = false;
bool oq_meassure_enabled_tmp = fsensor_oq_meassure_enabled;
fsensor_oq_meassure_enabled = true;
fsensor_stop_and_save_print();
// move the nozzle away while checking the filament
current_position[Z_AXIS] += 0.8;
if(current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder);
st_synchronize();
fsensor_err_cnt = 0;
// check the filament in isolation
fsensor_reset_err_cnt();
fsensor_oq_meassure_start(0);
enquecommand_front_P((PSTR("G1 E-3 F200")));
process_commands();
KEEPALIVE_STATE(IN_HANDLER);
cmdqueue_pop_front();
st_synchronize();
enquecommand_front_P((PSTR("G1 E3 F200")));
process_commands();
KEEPALIVE_STATE(IN_HANDLER);
cmdqueue_pop_front();
st_synchronize();
uint8_t err_cnt = fsensor_err_cnt;
float e_tmp = current_position[E_AXIS];
current_position[E_AXIS] -= 3;
plan_buffer_line_curposXYZE(250/60, active_extruder);
current_position[E_AXIS] = e_tmp;
plan_buffer_line_curposXYZE(200/60, active_extruder);
st_synchronize();
fsensor_oq_meassure_stop();
bool err = false;
err |= (err_cnt > 1);
err |= (fsensor_oq_er_sum > 2);
err |= (fsensor_oq_yd_sum < (4 * FSENSOR_OQ_MIN_YD));
err |= (fsensor_err_cnt > 0); // final error count is non-zero
err |= (fsensor_oq_er_sum > FSENSOR_OQ_MAX_ES); // total error count is above limit
err |= (fsensor_oq_yd_sum < FSENSOR_OQ_MIN_YD); // total measured distance is below limit
fsensor_restore_print_and_continue();
fsensor_autoload_enabled = autoload_enabled_tmp;
fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp;
fsensor_autoload_enabled = autoload_enabled_tmp;
fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp;
if (!err)
printf_P(PSTR("fsensor_err_cnt = 0\n"));
else
fsensor_enque_M600();
unsigned long now = _millis();
if (!err && (now - fsensor_softfail_last) > FSENSOR_SOFTERR_DELTA)
fsensor_softfail_ccnt = 0;
if (!err && fsensor_softfail_ccnt <= FSENSOR_SOFTERR_CMAX)
{
printf_P(PSTR("fsensor_err_cnt = 0\n"));
++fsensor_softfail;
++fsensor_softfail_ccnt;
fsensor_softfail_last = now;
}
else
{
fsensor_softfail_ccnt = 0;
fsensor_softfail_last = 0;
fsensor_enque_M600();
}
}
#else //PAT9125
if (CHECK_FSENSOR && fsensor_enabled && ir_sensor_detected)
if (CHECK_FSENSOR && ir_sensor_detected)
{
if(digitalRead(IR_SENSOR_PIN))
{ // IR_SENSOR_PIN ~ H

View File

@ -6,15 +6,16 @@
#include "config.h"
//! minimum meassured chunk length in steps
extern int16_t fsensor_chunk_len;
// enable/disable flag
extern bool fsensor_enabled;
// not responding flag
extern bool fsensor_not_responding;
//enable/disable quality meassurement
extern bool fsensor_oq_meassure_enabled;
#ifdef PAT9125
// optical checking "chunk lenght" (already in steps)
extern int16_t fsensor_chunk_len;
// count of soft failures
extern uint8_t fsensor_softfail;
#endif
//! @name save restore printing
//! @{
@ -28,6 +29,11 @@ extern void fsensor_checkpoint_print(void);
//! initialize
extern void fsensor_init(void);
#ifdef PAT9125
//! update axis resolution
extern void fsensor_set_axis_steps_per_unit(float u);
#endif
//! @name enable/disable
//! @{
extern bool fsensor_enable(bool bUpdateEEPROM=true);
@ -52,21 +58,27 @@ extern void fsensor_autoload_check_stop(void);
extern bool fsensor_check_autoload(void);
//! @}
#ifdef PAT9125
//! @name optical quality measurement support
//! @{
extern bool fsensor_oq_meassure_enabled;
extern void fsensor_oq_meassure_set(bool State);
extern void fsensor_oq_meassure_start(uint8_t skip);
extern void fsensor_oq_meassure_stop(void);
extern bool fsensor_oq_result(void);
//! @}
#include "planner.h"
//! @name callbacks from stepper
//! @{
extern void fsensor_st_block_begin(block_t* bl);
extern void fsensor_st_block_chunk(block_t* bl, int cnt);
extern void fsensor_st_block_chunk(int cnt);
// 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
// to drain fsensor_st_cnt anyway at the beginning of the new block.
#define fsensor_st_block_begin(rev) fsensor_st_block_chunk(0)
//! @}
#endif //PAT9125
#if IR_SENSOR_ANALOG

View File

@ -45,6 +45,12 @@
// 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
@ -61,6 +67,8 @@ enum class States : uint8_t {
///! 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)
@ -93,6 +101,7 @@ 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
@ -136,6 +145,7 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine
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;

88
Firmware/la10compat.cpp Normal file
View File

@ -0,0 +1,88 @@
#include "la10compat.h"
#include "Marlin.h"
static LA10C_MODE la10c_mode = LA10C_UNKNOWN; // Current LA compatibility mode
static float la10c_orig_jerk = 0; // Unadjusted/saved e-jerk
LA10C_MODE la10c_mode_get()
{
return la10c_mode;
}
void la10c_mode_change(LA10C_MODE mode)
{
if(mode == la10c_mode) return;
// always restore to the last unadjusted E-jerk value
if(la10c_orig_jerk)
cs.max_jerk[E_AXIS] = la10c_orig_jerk;
SERIAL_ECHOPGM("LA10C: Linear Advance mode: ");
switch(mode)
{
case LA10C_UNKNOWN: SERIAL_ECHOLNPGM("UNKNOWN"); break;
case LA10C_LA15: SERIAL_ECHOLNPGM("1.5"); break;
case LA10C_LA10: SERIAL_ECHOLNPGM("1.0"); break;
}
la10c_mode = mode;
// adjust the E-jerk if needed
cs.max_jerk[E_AXIS] = la10c_jerk(cs.max_jerk[E_AXIS]);
}
// Approximate a LA10 value to a LA15 equivalent.
static float la10c_convert(float k)
{
float new_K = k * 0.004 - 0.06;
return (new_K < 0? 0: new_K);
}
float la10c_value(float k)
{
if(la10c_mode == LA10C_UNKNOWN)
{
// do not autodetect until a valid value is seen
if(k == 0)
return 0;
else if(k < 0)
return -1;
la10c_mode_change(k < 10? LA10C_LA15: LA10C_LA10);
}
if(la10c_mode == LA10C_LA15)
return (k >= 0 && k < 10? k: -1);
else
return (k >= 0? la10c_convert(k): -1);
}
float la10c_jerk(float j)
{
la10c_orig_jerk = j;
if(la10c_mode != LA10C_LA10)
return j;
// check for a compatible range of values prior to convert (be sure that
// a higher E-jerk would still be compatible wrt the E accell range)
if(j < 4.5 && cs.max_acceleration_units_per_sq_second_normal[E_AXIS] < 2000)
return j;
// bring low E-jerk values into equivalent LA 1.5 values by
// flattening the response in the (1-4.5) range using a piecewise
// function. Is it truly worth to preserve the difference between
// 1.5/2.5 E-jerk for LA1.0? Probably not, but we try nonetheless.
j = j < 1.0? j * 3.625:
j < 4.5? j * 0.25 + 3.375:
j;
SERIAL_ECHOPGM("LA10C: Adjusted E-Jerk: ");
SERIAL_ECHOLN(j);
return j;
}

46
Firmware/la10compat.h Normal file
View File

@ -0,0 +1,46 @@
// la10compat: LA10->LA15 conversion
//
// When the current mode is UNKNOWN autodetection is active and any K<10
// will set the mode to LA15, LA10 is set otherwise. When LA10
// compatbility mode is active the K factor is converted to a LA15
// equivalent (that is, the return value is always a LA15 value).
//
// E-jerk<2 is also bumped in LA10 mode to restore the the printing speed
// to values comparable to existing settings.
//
// Once the interpretation mode has been set it is kept until the mode
// is explicitly reset. This is done to handle transparent fallback for
// old firmware revisions in combination with the following gcode
// sequence:
//
// M900 K0.01 ; set LA15 value (interpreted by any firmware)
// M900 K10 ; set LA10 value (ignored by LA15 firmware)
//
// A LA15 firmware without this module will only parse the first
// correctly, rejecting the second. A LA10 FW will parse both, but keep
// the last value. Since the LA15 value, if present, corresponds to the
// truth value, the compatibility stub needs to "lock" onto the first
// seen value for the current print.
//
// The mode needs to be carefully reset for each print in order for
// diffent versions of M900 to be interpreted independently.
#pragma once
enum __attribute__((packed)) LA10C_MODE
{
LA10C_UNKNOWN = 0,
LA10C_LA15 = 1,
LA10C_LA10 = 2
};
// Explicitly set/get/reset the interpretation mode for la10c_value()
void la10c_mode_change(LA10C_MODE mode);
LA10C_MODE la10c_mode_get();
static inline void la10c_reset() { la10c_mode_change(LA10C_UNKNOWN); }
// Return a LA15 K value according to the supplied value and mode
float la10c_value(float k);
// Return an updated LA15 E-jerk value according to the current mode
float la10c_jerk(float j);

View File

@ -103,7 +103,7 @@ void menu_back(void)
menu_back(1);
}
static void menu_back_no_reset(void)
void menu_back_no_reset(void)
{
if (menu_depth > 0)
{
@ -146,7 +146,7 @@ void menu_submenu(menu_func_t submenu)
}
}
static void menu_submenu_no_reset(menu_func_t submenu)
void menu_submenu_no_reset(menu_func_t submenu)
{
if (menu_depth < MENU_DEPTH_MAX)
{

View File

@ -76,6 +76,7 @@ void menu_start(void);
extern void menu_end(void);
extern void menu_back(void);
extern void menu_back_no_reset(void);
extern void menu_back(uint8_t nLevel);
extern void menu_back_scroll(int scrollback);
@ -85,6 +86,7 @@ extern void menu_back_if_clicked(void);
extern void menu_back_if_clicked_fb(void);
extern void menu_submenu(menu_func_t submenu);
extern void menu_submenu_no_reset(menu_func_t submenu);
extern void menu_submenu_scroll(menu_func_t submenu);
@ -135,7 +137,6 @@ extern const char menu_fmt_int3[];
extern const char menu_fmt_float31[];
extern const char menu_fmt_float13[];
extern void menu_draw_float31(const char* str, float val);
extern void menu_draw_float13(const char* str, float val);

View File

@ -6,6 +6,7 @@
#include "mesh_bed_leveling.h"
#include "stepper.h"
#include "ultralcd.h"
#include "temperature.h"
#ifdef TMC2130
#include "tmc2130.h"
@ -946,6 +947,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i
)
{
bool high_deviation_occured = false;
bedPWMDisabled = 1;
#ifdef TMC2130
FORCE_HIGH_POWER_START;
#endif
@ -1044,6 +1046,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i
#ifdef TMC2130
FORCE_HIGH_POWER_END;
#endif
bedPWMDisabled = 0;
return true;
error:
@ -1053,6 +1056,7 @@ error:
#ifdef TMC2130
FORCE_HIGH_POWER_END;
#endif
bedPWMDisabled = 0;
return false;
}

View File

@ -168,3 +168,5 @@ const char MSG_OCTOPRINT_CANCEL[] PROGMEM_N1 = "// action:cancel"; ////
const char MSG_FANCHECK_EXTRUDER[] PROGMEM_N1 = "Err: EXTR. FAN ERROR"; ////c=20
const char MSG_FANCHECK_PRINT[] PROGMEM_N1 = "Err: PRINT FAN ERROR"; ////c=20
const char MSG_M112_KILL[] PROGMEM_N1 = "M112 called. Emergency Stop."; ////c=20
const char MSG_ADVANCE_K[] PROGMEM_N1 = "Advance K:"; ////c=13
const char MSG_POWERPANIC_DETECTED[] PROGMEM_N1 = "POWER PANIC DETECTED"; ////c=20

View File

@ -169,6 +169,8 @@ extern const char MSG_OCTOPRINT_CANCEL[];
extern const char MSG_FANCHECK_EXTRUDER[];
extern const char MSG_FANCHECK_PRINT[];
extern const char MSG_M112_KILL[];
extern const char MSG_ADVANCE_K[];
extern const char MSG_POWERPANIC_DETECTED[];
#if defined(__cplusplus)
}

View File

@ -1547,7 +1547,7 @@ void mmu_continue_loading(bool blocking)
};
Ls state = Ls::Enter;
const uint_least8_t max_retry = 2;
const uint_least8_t max_retry = 3;
uint_least8_t retry = 0;
while (!success)
@ -1589,6 +1589,7 @@ void mmu_continue_loading(bool blocking)
if (blocking)
{
marlin_wait_for_click();
st_synchronize();
restore_print_from_ram_and_continue(0);
state = Ls::Retry;
}

View File

@ -183,9 +183,9 @@ uint8_t pat9125_update(void)
if (pat9125_PID1 == 0xff) return 0;
if (ucMotion & 0x80)
{
uint8_t ucXL = pat9125_rd_reg(PAT9125_DELTA_XL);
uint8_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
uint8_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
uint16_t ucXL = pat9125_rd_reg(PAT9125_DELTA_XL);
uint16_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
uint16_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
if (pat9125_PID1 == 0xff) return 0;
int16_t iDX = ucXL | ((ucXYH << 4) & 0xf00);
int16_t iDY = ucYL | ((ucXYH << 8) & 0xf00);
@ -207,8 +207,8 @@ uint8_t pat9125_update_y(void)
if (pat9125_PID1 == 0xff) return 0;
if (ucMotion & 0x80)
{
uint8_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
uint8_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
uint16_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
uint16_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
if (pat9125_PID1 == 0xff) return 0;
int16_t iDY = ucYL | ((ucXYH << 8) & 0xf00);
if (iDY & 0x800) iDY -= 4096;
@ -219,18 +219,13 @@ uint8_t pat9125_update_y(void)
return 0;
}
uint8_t pat9125_update_y2(void)
uint8_t pat9125_update_bs(void)
{
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
{
uint8_t ucMotion = pat9125_rd_reg(PAT9125_MOTION);
if (pat9125_PID1 == 0xff) return 0; //NOACK error
if (ucMotion & 0x80)
{
int8_t dy = pat9125_rd_reg(PAT9125_DELTA_YL);
if (pat9125_PID1 == 0xff) return 0; //NOACK error
pat9125_y -= dy; //negative number, because direction switching does not work
}
pat9125_b = pat9125_rd_reg(PAT9125_FRAME);
pat9125_s = pat9125_rd_reg(PAT9125_SHUTTER);
if (pat9125_PID1 == 0xff) return 0;
return 1;
}
return 0;

View File

@ -19,9 +19,9 @@ extern uint8_t pat9125_b;
extern uint8_t pat9125_s;
extern uint8_t pat9125_init(void);
extern uint8_t pat9125_update(void);
extern uint8_t pat9125_update_y(void);
extern uint8_t pat9125_update_y2(void);
extern uint8_t pat9125_update(void); // update all sensor data
extern uint8_t pat9125_update_y(void); // update _y only
extern uint8_t pat9125_update_bs(void); // update _b/_s only
#if defined(__cplusplus)

View File

@ -126,11 +126,14 @@ float extrude_min_temp=EXTRUDE_MINTEMP;
#endif
#ifdef LIN_ADVANCE
float extruder_advance_k = LIN_ADVANCE_K,
advance_ed_ratio = LIN_ADVANCE_E_D_RATIO,
position_float[NUM_AXIS] = { 0 };
float extruder_advance_K = LIN_ADVANCE_K;
float position_float[NUM_AXIS];
#endif
// Request the next block to start at zero E count
static bool plan_reset_next_e_queue;
static bool plan_reset_next_e_sched;
// Returns the index of the next block in the ring buffer
// NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication.
static inline int8_t next_block_index(int8_t block_index) {
@ -262,6 +265,13 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
}
}
#ifdef LIN_ADVANCE
uint16_t final_adv_steps = 0;
if (block->use_advance_lead) {
final_adv_steps = exit_speed * block->adv_comp;
}
#endif
CRITICAL_SECTION_START; // Fill variables used by the stepper in a critical section
// This block locks the interrupts globally for 4.38 us,
// which corresponds to a maximum repeat frequency of 228.57 kHz.
@ -272,6 +282,9 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
block->decelerate_after = accelerate_steps+plateau_steps;
block->initial_rate = initial_rate;
block->final_rate = final_rate;
#ifdef LIN_ADVANCE
block->final_adv_steps = final_adv_steps;
#endif
}
CRITICAL_SECTION_END;
}
@ -424,14 +437,16 @@ void plan_init() {
block_buffer_head = 0;
block_buffer_tail = 0;
memset(position, 0, sizeof(position)); // clear position
#ifdef LIN_ADVANCE
memset(position_float, 0, sizeof(position)); // clear position
#endif
#ifdef LIN_ADVANCE
memset(position_float, 0, sizeof(position_float)); // clear position
#endif
previous_speed[0] = 0.0;
previous_speed[1] = 0.0;
previous_speed[2] = 0.0;
previous_speed[3] = 0.0;
previous_nominal_speed = 0.0;
plan_reset_next_e_queue = false;
plan_reset_next_e_sched = false;
}
@ -639,7 +654,9 @@ void planner_abort_hard()
// Apply inverse world correction matrix.
machine2world(current_position[X_AXIS], current_position[Y_AXIS]);
memcpy(destination, current_position, sizeof(destination));
#ifdef LIN_ADVANCE
memcpy(position_float, current_position, sizeof(position_float));
#endif
// Resets planner junction speeds. Assumes start from rest.
previous_nominal_speed = 0.0;
previous_speed[0] = 0.0;
@ -647,6 +664,9 @@ void planner_abort_hard()
previous_speed[2] = 0.0;
previous_speed[3] = 0.0;
plan_reset_next_e_queue = false;
plan_reset_next_e_sched = false;
// Relay to planner wait routine, that the current line shall be canceled.
waiting_inside_plan_buffer_line_print_aborted = true;
}
@ -710,6 +730,20 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
// Save the global feedrate at scheduling time
block->gcode_feedrate = feedrate;
// Reset the starting E position when requested
if (plan_reset_next_e_queue)
{
position[E_AXIS] = 0;
#ifdef LIN_ADVANCE
position_float[E_AXIS] = 0;
#endif
// the block might still be discarded later, but we need to ensure the lower-level
// count_position is also reset correctly for consistent results!
plan_reset_next_e_queue = false;
plan_reset_next_e_sched = true;
}
#ifdef ENABLE_AUTO_BED_LEVELING
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#endif // ENABLE_AUTO_BED_LEVELING
@ -775,21 +809,15 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
#endif // ENABLE_MESH_BED_LEVELING
target[E_AXIS] = lround(e*cs.axis_steps_per_unit[E_AXIS]);
#ifdef LIN_ADVANCE
const float mm_D_float = sqrt(sq(x - position_float[X_AXIS]) + sq(y - position_float[Y_AXIS]));
float de_float = e - position_float[E_AXIS];
#endif
#ifdef PREVENT_DANGEROUS_EXTRUDE
if(target[E_AXIS]!=position[E_AXIS])
{
if(degHotend(active_extruder)<extrude_min_temp)
{
position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part
#ifdef LIN_ADVANCE
#ifdef LIN_ADVANCE
position_float[E_AXIS] = e;
de_float = 0;
#endif
#endif
SERIAL_ECHO_START;
SERIAL_ECHOLNRPGM(_n(" cold extrusion prevented"));////MSG_ERR_COLD_EXTRUDE_STOP
}
@ -798,10 +826,9 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
if(labs(target[E_AXIS]-position[E_AXIS])>cs.axis_steps_per_unit[E_AXIS]*EXTRUDE_MAXLENGTH)
{
position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part
#ifdef LIN_ADVANCE
position_float[E_AXIS] = e;
de_float = 0;
#endif
#ifdef LIN_ADVANCE
position_float[E_AXIS] = e;
#endif
SERIAL_ECHO_START;
SERIAL_ECHOLNRPGM(_n(" too long extrusion prevented"));////MSG_ERR_LONG_EXTRUDE_STOP
}
@ -1012,6 +1039,9 @@ Having the real displacement of the head, we can calculate the total movement le
block->nominal_rate *= speed_factor;
}
#ifdef LIN_ADVANCE
float e_D_ratio = 0;
#endif
// Compute and limit the acceleration rate for the trapezoid generator.
// block->step_event_count ... event count of the fastest axis
// block->millimeters ... Euclidian length of the XYZ movement or the E length, if no XYZ movement.
@ -1019,10 +1049,51 @@ Having the real displacement of the head, we can calculate the total movement le
if(block->steps_x.wide == 0 && block->steps_y.wide == 0 && block->steps_z.wide == 0)
{
block->acceleration_st = ceil(cs.retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
#ifdef LIN_ADVANCE
block->use_advance_lead = false;
#endif
}
else
{
block->acceleration_st = ceil(cs.acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
#ifdef LIN_ADVANCE
/**
* 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[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
&& abs(delta_mm[Z_AXIS]) < 0.5;
if (block->use_advance_lead) {
e_D_ratio = (e - position_float[E_AXIS]) /
sqrt(sq(x - position_float[X_AXIS])
+ sq(y - position_float[Y_AXIS])
+ sq(z - position_float[Z_AXIS]));
// Check for unusual high e_D ratio to detect if a retract move was combined with the last
// print move due to min. steps per segment. Never execute this with advance! This assumes
// no one will use a retract length of 0mm < retr_length < ~0.2mm and no one will print
// 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;
#ifdef LA_DEBUG
SERIAL_ECHOLNPGM("LA: Block acceleration limited due to max E-jerk");
#endif
}
}
}
#endif
// Limit acceleration per axis
//FIXME Vojtech: One shall rather limit a projection of the acceleration vector instead of using the limit.
if(((float)block->acceleration_st * (float)block->steps_x.wide / (float)block->step_event_count.wide) > axis_steps_per_sqr_second[X_AXIS])
@ -1055,6 +1126,47 @@ Having the real displacement of the head, we can calculate the total movement le
block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
#ifdef LIN_ADVANCE
if (block->use_advance_lead) {
// the nominal speed doesn't change past this point: calculate the compression ratio for the
// segment and the required advance steps
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;
// 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) {
block->advance_rate = advance_rate * 4;
block->advance_step_loops = 4;
}
else if (advance_speed > 10000) {
block->advance_rate = advance_rate * 2;
block->advance_step_loops = 2;
}
else
{
// never overflow the internal accumulator with very low rates
if (advance_rate < UINT16_MAX)
block->advance_rate = advance_rate;
else
block->advance_rate = UINT16_MAX;
block->advance_step_loops = 1;
}
#ifdef LA_DEBUG
if (block->advance_step_loops > 2)
// @wavexx: we should really check for the difference between step_loops and
// advance_step_loops instead. A difference of more than 1 will lead
// to uneven speed and *should* be adjusted here by furthermore
// reducing the speed.
SERIAL_ECHOLNPGM("LA: More than 2 steps per eISR loop executed.");
#endif
}
#endif
// Start with a safe speed.
// Safe speed is the speed, from which the machine may halt to stop immediately.
float safe_speed = block->nominal_speed;
@ -1083,6 +1195,13 @@ Having the real displacement of the head, we can calculate the total movement le
// Reset the block flag.
block->flag = 0;
if (plan_reset_next_e_sched)
{
// finally propagate a pending reset
block->flag |= BLOCK_FLAG_E_RESET;
plan_reset_next_e_sched = false;
}
// Initial limit on the segment entry velocity.
float vmax_junction;
@ -1171,37 +1290,6 @@ Having the real displacement of the head, we can calculate the total movement le
previous_nominal_speed = block->nominal_speed;
previous_safe_speed = safe_speed;
#ifdef LIN_ADVANCE
//
// Use LIN_ADVANCE for blocks if all these are true:
//
// esteps : We have E steps todo (a printing move)
//
// block->steps[X_AXIS] || block->steps[Y_AXIS] : We have a movement in XY direction (i.e., not retract / prime).
//
// extruder_advance_k : There is an advance factor set.
//
// block->steps[E_AXIS] != block->step_event_count : A problem occurs if the move before a retract is too small.
// In that case, the retract and move will be executed together.
// This leads to too many advance steps due to a huge e_acceleration.
// The math is good, but we must avoid retract moves with advance!
// de_float > 0.0 : Extruder is running forward (e.g., for "Wipe while retracting" (Slic3r) or "Combing" (Cura) moves)
//
block->use_advance_lead = block->steps_e.wide
&& (block->steps_x.wide || block->steps_y.wide)
&& extruder_advance_k
&& (uint32_t)block->steps_e.wide != block->step_event_count.wide
&& de_float > 0.0;
if (block->use_advance_lead)
block->abs_adv_steps_multiplier8 = lround(
extruder_advance_k
* ((advance_ed_ratio < 0.000001) ? de_float / mm_D_float : advance_ed_ratio) // Use the fixed ratio, if set
* (block->nominal_speed / (float)block->nominal_rate)
* cs.axis_steps_per_unit[E_AXIS] * 256.0
);
#endif
// Precalculate the division, so when all the trapezoids in the planner queue get recalculated, the division is not repeated.
block->speed_factor = block->nominal_rate / block->nominal_speed;
calculate_trapezoid_for_block(block, block->entry_speed, safe_speed);
@ -1215,12 +1303,12 @@ Having the real displacement of the head, we can calculate the total movement le
// Update position
memcpy(position, target, sizeof(target)); // position[] = target[]
#ifdef LIN_ADVANCE
#ifdef LIN_ADVANCE
position_float[X_AXIS] = x;
position_float[Y_AXIS] = y;
position_float[Z_AXIS] = z;
position_float[E_AXIS] = e;
#endif
#endif
// Recalculate the trapezoids to maximize speed at the segment transitions while respecting
// the machine limits (maximum acceleration and maximum jerk).
@ -1264,14 +1352,7 @@ void plan_set_position(float x, float y, float z, const float &e)
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#endif // ENABLE_AUTO_BED_LEVELING
// Apply the machine correction matrix.
if (world2machine_correction_mode != WORLD2MACHINE_CORRECTION_NONE)
{
float tmpx = x;
float tmpy = y;
x = world2machine_rotation_and_skew[0][0] * tmpx + world2machine_rotation_and_skew[0][1] * tmpy + world2machine_shift[0];
y = world2machine_rotation_and_skew[1][0] * tmpx + world2machine_rotation_and_skew[1][1] * tmpy + world2machine_shift[1];
}
world2machine(x, y);
position[X_AXIS] = lround(x*cs.axis_steps_per_unit[X_AXIS]);
position[Y_AXIS] = lround(y*cs.axis_steps_per_unit[Y_AXIS]);
@ -1283,12 +1364,12 @@ void plan_set_position(float x, float y, float z, const float &e)
position[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]);
#endif // ENABLE_MESH_BED_LEVELING
position[E_AXIS] = lround(e*cs.axis_steps_per_unit[E_AXIS]);
#ifdef LIN_ADVANCE
#ifdef LIN_ADVANCE
position_float[X_AXIS] = x;
position_float[Y_AXIS] = y;
position_float[Z_AXIS] = z;
position_float[E_AXIS] = e;
#endif
#endif
st_set_position(position[X_AXIS], position[Y_AXIS], position[Z_AXIS], position[E_AXIS]);
previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest.
previous_speed[0] = 0.0;
@ -1300,11 +1381,11 @@ void plan_set_position(float x, float y, float z, const float &e)
// Only useful in the bed leveling routine, when the mesh bed leveling is off.
void plan_set_z_position(const float &z)
{
#ifdef LIN_ADVANCE
position_float[Z_AXIS] = z;
#endif
position[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]);
st_set_position(position[X_AXIS], position[Y_AXIS], position[Z_AXIS], position[E_AXIS]);
#ifdef LIN_ADVANCE
position_float[Z_AXIS] = z;
#endif
position[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]);
st_set_position(position[X_AXIS], position[Y_AXIS], position[Z_AXIS], position[E_AXIS]);
}
void plan_set_e_position(const float &e)
@ -1316,6 +1397,11 @@ void plan_set_e_position(const float &e)
st_set_e_position(position[E_AXIS]);
}
void plan_reset_next_e()
{
plan_reset_next_e_queue = true;
}
#ifdef PREVENT_DANGEROUS_EXTRUDE
void set_extrude_min_temp(float temp)
{

View File

@ -44,6 +44,8 @@ enum BlockFlag {
// than 32767, therefore the DDA algorithm may run with 16bit resolution only.
// In addition, the stepper routine will not do any end stop checking for higher performance.
BLOCK_FLAG_DDA_LOWRES = 8,
// Block starts with Zeroed E counter
BLOCK_FLAG_E_RESET = 16,
};
union dda_isteps_t
@ -110,10 +112,14 @@ typedef struct {
// Pre-calculated division for the calculate_trapezoid_for_block() routine to run faster.
float speed_factor;
#ifdef LIN_ADVANCE
bool use_advance_lead;
unsigned long abs_adv_steps_multiplier8; // Factorised by 2^8 to avoid float
bool use_advance_lead; // Whether the current block uses LA
uint16_t advance_rate, // Step-rate for extruder speed
max_adv_steps, // max. advance steps to get cruising speed pressure (not always nominal_speed!)
final_adv_steps; // advance steps due to exit speed
uint8_t advance_step_loops; // Number of stepper ticks for each advance isr
float adv_comp; // Precomputed E compression factor
#endif
// Save/recovery state data
@ -123,7 +129,7 @@ typedef struct {
} block_t;
#ifdef LIN_ADVANCE
extern float extruder_advance_k, advance_ed_ratio;
extern float extruder_advance_K; // Linear-advance K factor
#endif
#ifdef ENABLE_AUTO_BED_LEVELING
@ -164,6 +170,9 @@ void plan_set_position(float x, float y, float z, const float &e);
void plan_set_z_position(const float &z);
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();
extern bool e_active();
void check_axes_activity();

View File

@ -0,0 +1,147 @@
#include "speed_lookuptable.h"
#if F_CPU == 16000000
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
{ 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135},
{ 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32},
{ 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14},
{ 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8},
{ 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5},
{ 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3},
{ 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2},
{ 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2},
{ 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1},
{ 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1},
{ 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1},
{ 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1},
{ 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0},
{ 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1},
{ 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0},
{ 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1},
{ 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0},
{ 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0},
{ 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0},
{ 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1},
{ 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0},
{ 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0},
{ 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0},
{ 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0},
{ 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0},
{ 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0},
{ 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0},
{ 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1},
{ 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0},
{ 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0},
{ 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0},
{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
};
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
{ 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894},
{ 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657},
{ 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331},
{ 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198},
{ 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132},
{ 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94},
{ 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71},
{ 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55},
{ 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44},
{ 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36},
{ 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30},
{ 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25},
{ 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22},
{ 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18},
{ 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16},
{ 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15},
{ 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13},
{ 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11},
{ 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10},
{ 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9},
{ 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8},
{ 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8},
{ 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7},
{ 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7},
{ 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6},
{ 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5},
{ 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5},
{ 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5},
{ 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4},
{ 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4},
{ 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4},
{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
};
#elif F_CPU == 20000000
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
{62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167},
{1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40},
{604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17},
{404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10},
{303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6},
{243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5},
{202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4},
{173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2},
{152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2},
{135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2},
{121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2},
{110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1},
{101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1},
{93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0},
{87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0},
{81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0},
{76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1},
{71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1},
{67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0},
{64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1},
{60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0},
{58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0},
{55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0},
{53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1},
{50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1},
{48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1},
{46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0},
{45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0},
{43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0},
{42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0},
{40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0},
{39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0},
};
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
{62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003},
{24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745},
{14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385},
{10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235},
{8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158},
{6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113},
{5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86},
{5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67},
{4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53},
{4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44},
{3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36},
{3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31},
{3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27},
{2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23},
{2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20},
{2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18},
{2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16},
{2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14},
{2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13},
{1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12},
{1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10},
{1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10},
{1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9},
{1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8},
{1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7},
{1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7},
{1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6},
{1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6},
{1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6},
{1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5},
{1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5},
{1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5},
};
#endif

View File

@ -3,150 +3,123 @@
#include "Marlin.h"
#if F_CPU == 16000000
extern const uint16_t speed_lookuptable_fast[256][2] PROGMEM;
extern const uint16_t speed_lookuptable_slow[256][2] PROGMEM;
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
{ 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135},
{ 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32},
{ 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14},
{ 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8},
{ 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5},
{ 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3},
{ 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2},
{ 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2},
{ 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1},
{ 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1},
{ 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1},
{ 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1},
{ 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0},
{ 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1},
{ 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0},
{ 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1},
{ 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0},
{ 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0},
{ 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0},
{ 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1},
{ 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0},
{ 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0},
{ 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0},
{ 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0},
{ 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0},
{ 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0},
{ 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0},
{ 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1},
{ 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0},
{ 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0},
{ 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0},
{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
};
#ifndef _NO_ASM
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
{ 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894},
{ 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657},
{ 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331},
{ 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198},
{ 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132},
{ 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94},
{ 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71},
{ 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55},
{ 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44},
{ 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36},
{ 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30},
{ 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25},
{ 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22},
{ 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18},
{ 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16},
{ 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15},
{ 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13},
{ 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11},
{ 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10},
{ 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9},
{ 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8},
{ 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8},
{ 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7},
{ 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7},
{ 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6},
{ 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5},
{ 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5},
{ 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5},
{ 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4},
{ 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4},
{ 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4},
{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
};
// intRes = intIn1 * intIn2 >> 16
// uses:
// r26 to store 0
// r27 to store the byte 1 of the 24 bit result
#define MultiU16X8toH16(intRes, charIn1, intIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %A1, %A2 \n\t" \
"add %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r0 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (charIn1), \
"d" (intIn2) \
: \
"r26" \
)
#elif F_CPU == 20000000
// intRes = longIn1 * longIn2 >> 24
// uses:
// r26 to store 0
// r27 to store the byte 1 of the 48bit result
#define MultiU24X24toH16(intRes, longIn1, longIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"mov r27, r1 \n\t" \
"mul %B1, %C2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %C1, %C2 \n\t" \
"add %B0, r0 \n\t" \
"mul %C1, %B2 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %A1, %C2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %B2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %C1, %A2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %A2 \n\t" \
"add r27, r1 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r27 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (longIn1), \
"d" (longIn2) \
: \
"r26" , "r27" \
)
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
{62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167},
{1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40},
{604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17},
{404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10},
{303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6},
{243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5},
{202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4},
{173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2},
{152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2},
{135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2},
{121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2},
{110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1},
{101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1},
{93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0},
{87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0},
{81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0},
{76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1},
{71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1},
{67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0},
{64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1},
{60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0},
{58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0},
{55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0},
{53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1},
{50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1},
{48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1},
{46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0},
{45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0},
{43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0},
{42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0},
{40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0},
{39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0},
};
#else //_NO_ASM
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
{62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003},
{24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745},
{14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385},
{10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235},
{8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158},
{6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113},
{5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86},
{5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67},
{4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53},
{4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44},
{3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36},
{3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31},
{3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27},
{2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23},
{2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20},
{2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18},
{2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16},
{2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14},
{2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13},
{1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12},
{1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10},
{1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10},
{1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9},
{1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8},
{1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7},
{1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7},
{1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6},
{1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6},
{1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6},
{1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5},
{1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5},
{1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5},
};
#endif
// NOTE: currently not implemented
void MultiU16X8toH16(unsigned short& intRes, unsigned char& charIn1, unsigned short& intIn2);
void MultiU24X24toH16(uint16_t& intRes, int32_t& longIn1, long& longIn2);
#endif //_NO_ASM
FORCE_INLINE unsigned short calc_timer(uint16_t step_rate, uint8_t& step_loops) {
unsigned short timer;
if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
step_rate = (step_rate >> 2)&0x3fff;
step_loops = 4;
}
else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times
step_rate = (step_rate >> 1)&0x7fff;
step_loops = 2;
}
else {
step_loops = 1;
}
if(step_rate < (F_CPU/500000)) step_rate = (F_CPU/500000);
step_rate -= (F_CPU/500000); // Correct for minimal speed
if(step_rate >= (8*256)){ // higher step rate
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
unsigned char tmp_step_rate = (step_rate & 0x00ff);
unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
MultiU16X8toH16(timer, tmp_step_rate, gain);
timer = (unsigned short)pgm_read_word_near(table_address) - timer;
}
else { // lower step rates
unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
table_address += ((step_rate)>>1) & 0xfffc;
timer = (unsigned short)pgm_read_word_near(table_address);
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
}
if(timer < 100) { timer = 100; }//(20kHz this should never happen)////MSG_STEPPER_TOO_HIGH c=0 r=0
return timer;
}
#endif

View File

@ -36,9 +36,9 @@
#include "tmc2130.h"
#endif //TMC2130
#ifdef FILAMENT_SENSOR
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
#include "fsensor.h"
int fsensor_counter = 0; //counter for e-steps
int fsensor_counter; //counter for e-steps
#endif //FILAMENT_SENSOR
#include "mmu.h"
@ -113,23 +113,30 @@ volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
#ifdef LIN_ADVANCE
void advance_isr_scheduler();
void advance_isr();
static uint16_t nextMainISR = 0;
static const uint16_t ADV_NEVER = 0xFFFF;
static const uint8_t ADV_INIT = 0b01;
static const uint8_t ADV_DECELERATE = 0b10;
static uint16_t nextMainISR;
static uint16_t nextAdvanceISR;
static uint16_t main_Rate;
static uint16_t eISR_Rate;
static uint16_t eISR_Err;
// Extrusion steps to be executed by the stepper.
// If set to non zero, the timer ISR routine will tick the Linear Advance extruder ticks first.
// If e_steps is zero, then the timer ISR routine will perform the usual DDA step.
static volatile int16_t e_steps = 0;
// How many extruder steps shall be ticked at a single ISR invocation?
static uint8_t estep_loops;
// The current speed of the extruder, scaled by the linear advance constant, so it has the same measure
// as current_adv_steps.
static int current_estep_rate;
// The current pretension of filament expressed in extruder micro steps.
static int current_adv_steps;
static uint16_t current_adv_steps;
static uint16_t final_adv_steps;
static uint16_t max_adv_steps;
static uint32_t LA_decelerate_after;
#define _NEXT_ISR(T) nextMainISR = T
static int8_t e_steps;
static uint8_t e_step_loops;
static int8_t LA_phase;
#define _NEXT_ISR(T) main_Rate = nextMainISR = T
#else
#define _NEXT_ISR(T) OCR1A = T
#endif
@ -143,92 +150,6 @@ extern uint16_t stepper_timer_overflow_last;
//=============================functions ============================
//===========================================================================
#ifndef _NO_ASM
// intRes = intIn1 * intIn2 >> 16
// uses:
// r26 to store 0
// r27 to store the byte 1 of the 24 bit result
#define MultiU16X8toH16(intRes, charIn1, intIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %A1, %A2 \n\t" \
"add %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r0 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (charIn1), \
"d" (intIn2) \
: \
"r26" \
)
// intRes = longIn1 * longIn2 >> 24
// uses:
// r26 to store 0
// r27 to store the byte 1 of the 48bit result
#define MultiU24X24toH16(intRes, longIn1, longIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"mov r27, r1 \n\t" \
"mul %B1, %C2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %C1, %C2 \n\t" \
"add %B0, r0 \n\t" \
"mul %C1, %B2 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %A1, %C2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %B2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %C1, %A2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %A2 \n\t" \
"add r27, r1 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r27 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (longIn1), \
"d" (longIn2) \
: \
"r26" , "r27" \
)
#else //_NO_ASM
void MultiU16X8toH16(unsigned short& intRes, unsigned char& charIn1, unsigned short& intIn2)
{
}
void MultiU24X24toH16(uint16_t& intRes, int32_t& longIn1, long& longIn2)
{
}
#endif //_NO_ASM
// Some useful constants
void checkHitEndstops()
{
if( endstop_x_hit || endstop_y_hit || endstop_z_hit) {
@ -316,42 +237,6 @@ void invert_z_endstop(bool endstop_invert)
// step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
// The slope of acceleration is calculated with the leib ramp alghorithm.
FORCE_INLINE unsigned short calc_timer(uint16_t step_rate) {
unsigned short timer;
if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
step_rate = (step_rate >> 2)&0x3fff;
step_loops = 4;
}
else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times
step_rate = (step_rate >> 1)&0x7fff;
step_loops = 2;
}
else {
step_loops = 1;
}
// step_loops = 1;
if(step_rate < (F_CPU/500000)) step_rate = (F_CPU/500000);
step_rate -= (F_CPU/500000); // Correct for minimal speed
if(step_rate >= (8*256)){ // higher step rate
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
unsigned char tmp_step_rate = (step_rate & 0x00ff);
unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
MultiU16X8toH16(timer, tmp_step_rate, gain);
timer = (unsigned short)pgm_read_word_near(table_address) - timer;
}
else { // lower step rates
unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
table_address += ((step_rate)>>1) & 0xfffc;
timer = (unsigned short)pgm_read_word_near(table_address);
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
}
if(timer < 100) { timer = 100; MYSERIAL.print(_N("Steprate too high: ")); MYSERIAL.println(step_rate); }//(20kHz this should never happen)////MSG_STEPPER_TOO_HIGH
return timer;
}
// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
ISR(TIMER1_COMPA_vect) {
@ -361,53 +246,10 @@ ISR(TIMER1_COMPA_vect) {
#endif //DEBUG_STACK_MONITOR
#ifdef LIN_ADVANCE
// If there are any e_steps planned, tick them.
bool run_main_isr = false;
if (e_steps) {
//WRITE_NC(LOGIC_ANALYZER_CH7, true);
uint8_t cnt = 0;
for (uint8_t i = estep_loops; e_steps && i --;) {
WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
-- e_steps;
cnt++;
WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
}
#ifdef FILAMENT_SENSOR
if (READ(E0_DIR_PIN) == INVERT_E0_DIR)
{
if (count_direction[E_AXIS] == 1)
fsensor_counter -= cnt;
else
fsensor_counter += cnt;
}
else
{
if (count_direction[E_AXIS] == 1)
fsensor_counter += cnt;
else
fsensor_counter -= cnt;
}
#endif //FILAMENT_SENSOR
if (e_steps) {
// Plan another Linear Advance tick.
OCR1A = eISR_Rate;
nextMainISR -= eISR_Rate;
} else if (! (nextMainISR & 0x8000) || nextMainISR < 16) {
// The timer did not overflow and it is big enough, so it makes sense to plan it.
OCR1A = nextMainISR;
} else {
// The timer has overflown, or it is too small. Run the main ISR just after the Linear Advance routine
// in the current interrupt tick.
run_main_isr = true;
//FIXME pick the serial line.
}
//WRITE_NC(LOGIC_ANALYZER_CH7, false);
} else
run_main_isr = true;
if (run_main_isr)
#endif
advance_isr_scheduler();
#else
isr();
#endif
// Don't run the ISR faster than possible
// Is there a 8us time left before the next interrupt triggers?
@ -493,10 +335,6 @@ FORCE_INLINE void stepper_next_block()
}
#endif
#ifdef FILAMENT_SENSOR
fsensor_counter = 0;
fsensor_st_block_begin(current_block);
#endif //FILAMENT_SENSOR
// The busy flag is set by the plan_get_current_block() call.
// current_block->busy = true;
// Initializes the trapezoid generator from the current block. Called whenever a new
@ -507,10 +345,26 @@ FORCE_INLINE void stepper_next_block()
// state is reached.
step_loops_nominal = 0;
acc_step_rate = uint16_t(current_block->initial_rate);
acceleration_time = calc_timer(acc_step_rate);
acceleration_time = calc_timer(acc_step_rate, step_loops);
#ifdef LIN_ADVANCE
current_estep_rate = ((unsigned long)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
#endif /* 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;
} else {
e_steps = 0;
e_step_loops = 1;
current_adv_steps = 0;
}
nextAdvanceISR = ADV_NEVER;
LA_phase = -1;
#endif
if (current_block->flag & BLOCK_FLAG_E_RESET) {
count_position[E_AXIS] = 0;
}
if (current_block->flag & BLOCK_FLAG_DDA_LOWRES) {
counter_x.lo = -(current_block->step_event_count.lo >> 1);
@ -567,9 +421,23 @@ FORCE_INLINE void stepper_next_block()
#endif /* LIN_ADVANCE */
count_direction[E_AXIS] = 1;
}
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
fsensor_st_block_begin(count_direction[E_AXIS] < 0);
#endif //FILAMENT_SENSOR
}
else {
OCR1A = 2000; // 1kHz.
_NEXT_ISR(2000); // 1kHz.
#ifdef LIN_ADVANCE
// reset LA state when there's no block
nextAdvanceISR = ADV_NEVER;
e_steps = 0;
// incrementally lose pressure to give a chance for
// a new LA block to be scheduled and recover
if(current_adv_steps)
--current_adv_steps;
#endif
}
//WRITE_NC(LOGIC_ANALYZER_CH2, false);
}
@ -779,10 +647,10 @@ FORCE_INLINE void stepper_tick_lowres()
counter_e.lo -= current_block->step_event_count.lo;
count_position[E_AXIS] += count_direction[E_AXIS];
#ifdef LIN_ADVANCE
++ e_steps;
e_steps += count_direction[E_AXIS];
#else
#ifdef FILAMENT_SENSOR
++ fsensor_counter;
fsensor_counter += count_direction[E_AXIS];
#endif //FILAMENT_SENSOR
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
#endif
@ -841,11 +709,11 @@ FORCE_INLINE void stepper_tick_highres()
counter_e.wide -= current_block->step_event_count.wide;
count_position[E_AXIS]+=count_direction[E_AXIS];
#ifdef LIN_ADVANCE
++ e_steps;
e_steps += count_direction[E_AXIS];
#else
#ifdef FILAMENT_SENSOR
++ fsensor_counter;
#endif //FILAMENT_SENSOR
#ifdef FILAMENT_SENSOR
fsensor_counter += count_direction[E_AXIS];
#endif //FILAMENT_SENSOR
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
#endif
}
@ -854,8 +722,53 @@ FORCE_INLINE void stepper_tick_highres()
}
}
// 50us delay
#define LIN_ADV_FIRST_TICK_DELAY 100
#ifdef LIN_ADVANCE
// @wavexx: fast uint16_t division for small dividends<5
// q/3 based on "Hacker's delight" formula
FORCE_INLINE uint16_t fastdiv(uint16_t q, uint8_t d)
{
if(d != 3) return q >> (d / 2);
else return ((uint32_t)0xAAAB * q) >> 17;
}
FORCE_INLINE void advance_spread(uint16_t timer)
{
if(eISR_Err > timer)
{
// advance-step skipped
eISR_Err -= timer;
eISR_Rate = timer;
nextAdvanceISR = timer;
return;
}
// at least one step
uint8_t ticks = 1;
uint32_t block = current_block->advance_rate;
uint16_t max_t = timer - eISR_Err;
while (block < max_t)
{
++ticks;
block += current_block->advance_rate;
}
if (block > timer)
eISR_Err += block - timer;
else
eISR_Err -= timer - block;
if (ticks <= 4)
eISR_Rate = fastdiv(timer, ticks);
else
{
// >4 ticks are still possible on slow moves
eISR_Rate = timer / ticks;
}
nextAdvanceISR = eISR_Rate / 2;
}
#endif
FORCE_INLINE void isr() {
//WRITE_NC(LOGIC_ANALYZER_CH0, true);
@ -868,81 +781,18 @@ FORCE_INLINE void isr() {
if (current_block != NULL)
{
stepper_check_endstops();
#ifdef LIN_ADVANCE
e_steps = 0;
#endif /* LIN_ADVANCE */
if (current_block->flag & BLOCK_FLAG_DDA_LOWRES)
stepper_tick_lowres();
else
stepper_tick_highres();
#ifdef LIN_ADVANCE
if (out_bits&(1<<E_AXIS))
// Move in negative direction.
e_steps = - e_steps;
if (current_block->use_advance_lead) {
//int esteps_inc = 0;
//esteps_inc = current_estep_rate - current_adv_steps;
//e_steps += esteps_inc;
e_steps += current_estep_rate - current_adv_steps;
#if 0
if (abs(esteps_inc) > 4) {
LOGIC_ANALYZER_SERIAL_TX_WRITE(esteps_inc);
if (esteps_inc < -511 || esteps_inc > 511)
LOGIC_ANALYZER_SERIAL_TX_WRITE(esteps_inc >> 9);
}
#endif
current_adv_steps = current_estep_rate;
}
// If we have esteps to execute, step some of them now.
if (e_steps) {
//WRITE_NC(LOGIC_ANALYZER_CH7, true);
// Set the step direction.
bool neg = e_steps < 0;
{
bool dir =
#ifdef SNMM
(neg == (mmu_extruder & 1))
#else
neg
#endif
? INVERT_E0_DIR : !INVERT_E0_DIR; //If we have SNMM, reverse every second extruder.
WRITE_NC(E0_DIR_PIN, dir);
if (neg)
// Flip the e_steps counter to be always positive.
e_steps = - e_steps;
}
// Tick min(step_loops, abs(e_steps)).
estep_loops = (e_steps & 0x0ff00) ? 4 : e_steps;
if (step_loops < estep_loops)
estep_loops = step_loops;
#ifdef FILAMENT_SENSOR
if (READ(E0_DIR_PIN) == INVERT_E0_DIR)
{
if (count_direction[E_AXIS] == 1)
fsensor_counter -= estep_loops;
else
fsensor_counter += estep_loops;
}
else
{
if (count_direction[E_AXIS] == 1)
fsensor_counter += estep_loops;
else
fsensor_counter -= estep_loops;
}
#endif //FILAMENT_SENSOR
do {
WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
-- e_steps;
WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
} while (-- estep_loops != 0);
//WRITE_NC(LOGIC_ANALYZER_CH7, false);
MSerial.checkRx(); // Check for serial chars.
}
if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR);
uint8_t la_state = 0;
#endif
// Calculare new timer value
// Calculate new timer value
// 13.38-14.63us for steady state,
// 25.12us for acceleration / deceleration.
{
@ -955,14 +805,15 @@ FORCE_INLINE void isr() {
if(acc_step_rate > uint16_t(current_block->nominal_rate))
acc_step_rate = current_block->nominal_rate;
// step_rate to timer interval
uint16_t timer = calc_timer(acc_step_rate);
uint16_t timer = calc_timer(acc_step_rate, step_loops);
_NEXT_ISR(timer);
acceleration_time += timer;
#ifdef LIN_ADVANCE
if (current_block->use_advance_lead)
// int32_t = (uint16_t * uint32_t) >> 17
current_estep_rate = ((uint32_t)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
#endif
#ifdef LIN_ADVANCE
if (current_block->use_advance_lead) {
if (step_events_completed.wide <= (unsigned long int)step_loops)
la_state = ADV_INIT;
}
#endif
}
else if (step_events_completed.wide > (unsigned long int)current_block->decelerate_after) {
uint16_t step_rate;
@ -973,24 +824,23 @@ FORCE_INLINE void isr() {
step_rate = uint16_t(current_block->final_rate);
}
// Step_rate to timer interval.
uint16_t timer = calc_timer(step_rate);
uint16_t timer = calc_timer(step_rate, step_loops);
_NEXT_ISR(timer);
deceleration_time += timer;
#ifdef LIN_ADVANCE
if (current_block->use_advance_lead)
current_estep_rate = ((uint32_t)step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
#endif
#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;
}
#endif
}
else {
if (! step_loops_nominal) {
// Calculation of the steady state timer rate has been delayed to the 1st tick of the steady state to lower
// the initial interrupt blocking.
OCR1A_nominal = calc_timer(uint16_t(current_block->nominal_rate));
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)
current_estep_rate = (current_block->nominal_rate * current_block->abs_adv_steps_multiplier8) >> 17;
#endif
}
_NEXT_ISR(OCR1A_nominal);
}
@ -998,110 +848,40 @@ FORCE_INLINE void isr() {
}
#ifdef LIN_ADVANCE
if (e_steps && current_block->use_advance_lead) {
//WRITE_NC(LOGIC_ANALYZER_CH7, true);
MSerial.checkRx(); // Check for serial chars.
// Some of the E steps were not ticked yet. Plan additional interrupts.
uint16_t now = TCNT1;
// Plan the first linear advance interrupt after 50us from now.
uint16_t to_go = nextMainISR - now - LIN_ADV_FIRST_TICK_DELAY;
eISR_Rate = 0;
if ((to_go & 0x8000) == 0) {
// The to_go number is not negative.
// Count the number of 7812,5 ticks, that fit into to_go 2MHz ticks.
uint8_t ticks = to_go >> 8;
if (ticks == 1) {
// Avoid running the following loop for a very short interval.
estep_loops = 255;
eISR_Rate = 1;
} else if ((e_steps & 0x0ff00) == 0) {
// e_steps <= 0x0ff
if (uint8_t(e_steps) <= ticks) {
// Spread the e_steps along the whole go_to interval.
eISR_Rate = to_go / uint8_t(e_steps);
estep_loops = 1;
} else if (ticks != 0) {
// At least one tick fits into the to_go interval. Calculate the e-step grouping.
uint8_t e = uint8_t(e_steps) >> 1;
estep_loops = 2;
while (e > ticks) {
e >>= 1;
estep_loops <<= 1;
// 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 || nextAdvanceISR != ADV_NEVER) {
advance_spread(main_Rate);
if (la_state & ADV_DECELERATE) {
if (step_loops == e_step_loops)
LA_phase = (eISR_Rate > main_Rate);
else {
// avoid overflow through division. warning: we need to _guarantee_ step_loops
// and e_step_loops are <= 4 due to fastdiv's limit
LA_phase = (fastdiv(eISR_Rate, step_loops) > fastdiv(main_Rate, e_step_loops));
}
// Now the estep_loops contains the number of loops of power of 2, that will be sufficient
// to squeeze enough of Linear Advance ticks until nextMainISR.
// Calculate the tick rate.
eISR_Rate = to_go / ticks;
}
} else {
// This is an exterme case with too many e_steps inserted by the linear advance.
// At least one tick fits into the to_go interval. Calculate the e-step grouping.
estep_loops = 2;
uint16_t e = e_steps >> 1;
while (e & 0x0ff00) {
e >>= 1;
estep_loops <<= 1;
}
while (uint8_t(e) > ticks) {
e >>= 1;
estep_loops <<= 1;
}
// Now the estep_loops contains the number of loops of power of 2, that will be sufficient
// to squeeze enough of Linear Advance ticks until nextMainISR.
// Calculate the tick rate.
eISR_Rate = to_go / ticks;
}
}
if (eISR_Rate == 0) {
// There is not enough time to fit even a single additional tick.
// Tick all the extruder ticks now.
MSerial.checkRx(); // Check for serial chars.
#ifdef FILAMENT_SENSOR
if (READ(E0_DIR_PIN) == INVERT_E0_DIR)
{
if (count_direction[E_AXIS] == 1)
fsensor_counter -= e_steps;
else
fsensor_counter += e_steps;
}
else
{
if (count_direction[E_AXIS] == 1)
fsensor_counter += e_steps;
else
fsensor_counter -= e_steps;
}
#endif //FILAMENT_SENSOR
do {
WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
-- e_steps;
WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
} while (e_steps);
OCR1A = nextMainISR;
} else {
// Tick the 1st Linear Advance interrupt after 50us from now.
nextMainISR -= LIN_ADV_FIRST_TICK_DELAY;
OCR1A = now + LIN_ADV_FIRST_TICK_DELAY;
}
//WRITE_NC(LOGIC_ANALYZER_CH7, false);
} else
OCR1A = nextMainISR;
}
// Check for serial chars. This executes roughtly inbetween 50-60% of the total runtime of the
// entire isr, making this spot a much better choice than checking during esteps
MSerial.checkRx();
#endif
// If current block is finished, reset pointer
if (step_events_completed.wide >= current_block->step_event_count.wide) {
#ifdef FILAMENT_SENSOR
fsensor_st_block_chunk(current_block, fsensor_counter);
#if !defined(LIN_ADVANCE) && defined(FILAMENT_SENSOR)
fsensor_st_block_chunk(fsensor_counter);
fsensor_counter = 0;
#endif //FILAMENT_SENSOR
current_block = NULL;
plan_discard_current_block();
}
#ifdef FILAMENT_SENSOR
else if ((fsensor_counter >= fsensor_chunk_len))
#if !defined(LIN_ADVANCE) && defined(FILAMENT_SENSOR)
else if ((abs(fsensor_counter) >= fsensor_chunk_len))
{
fsensor_st_block_chunk(current_block, fsensor_counter);
fsensor_st_block_chunk(fsensor_counter);
fsensor_counter = 0;
}
#endif //FILAMENT_SENSOR
@ -1115,12 +895,105 @@ FORCE_INLINE void isr() {
}
#ifdef LIN_ADVANCE
// Timer interrupt for E. e_steps is set in the main routine.
void clear_current_adv_vars() {
e_steps = 0; //Should be already 0 at an filament change event, but just to be sure..
current_adv_steps = 0;
FORCE_INLINE void advance_isr() {
if (step_events_completed.wide > LA_decelerate_after && current_adv_steps > final_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);
if(current_adv_steps > e_step_loops)
current_adv_steps -= e_step_loops;
else
current_adv_steps = 0;
nextAdvanceISR = eISR_Rate;
}
else if (step_events_completed.wide < LA_decelerate_after && current_adv_steps < max_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);
current_adv_steps += e_step_loops;
nextAdvanceISR = eISR_Rate;
}
else {
// advance steps completed
nextAdvanceISR = ADV_NEVER;
LA_phase = -1;
e_step_loops = 1;
}
}
FORCE_INLINE void advance_isr_scheduler() {
// Integrate the final timer value, accounting for scheduling adjustments
if(nextAdvanceISR && nextAdvanceISR != ADV_NEVER)
{
if(nextAdvanceISR > OCR1A)
nextAdvanceISR -= OCR1A;
else
nextAdvanceISR = 0;
}
if(nextMainISR > OCR1A)
nextMainISR -= OCR1A;
else
nextMainISR = 0;
// Run main stepping ISR if flagged
if (!nextMainISR)
{
#ifdef LA_DEBUG_LOGIC
WRITE_NC(LOGIC_ANALYZER_CH0, true);
#endif
isr();
#ifdef LA_DEBUG_LOGIC
WRITE_NC(LOGIC_ANALYZER_CH0, false);
#endif
}
// Run the next advance isr if triggered
bool eisr = !nextAdvanceISR;
if (eisr)
{
#ifdef LA_DEBUG_LOGIC
WRITE_NC(LOGIC_ANALYZER_CH1, true);
#endif
advance_isr();
#ifdef LA_DEBUG_LOGIC
WRITE_NC(LOGIC_ANALYZER_CH1, false);
#endif
}
// Tick E steps if any
if (e_steps && (LA_phase < 0 || LA_phase == eisr)) {
uint8_t max_ticks = (eisr? e_step_loops: step_loops);
max_ticks = min(abs(e_steps), max_ticks);
bool rev = (e_steps < 0);
do
{
WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
e_steps += (rev? 1: -1);
WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
fsensor_counter += (rev? -1: 1);
#endif
}
while(--max_ticks);
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
if (abs(fsensor_counter) >= fsensor_chunk_len)
{
fsensor_st_block_chunk(fsensor_counter);
fsensor_counter = 0;
}
#endif
}
// Schedule the next closest tick, ignoring advance if scheduled too
// soon in order to avoid skewing the regular stepper acceleration
if (nextAdvanceISR != ADV_NEVER && (nextAdvanceISR + TCNT1 + 40) < nextMainISR)
OCR1A = nextAdvanceISR;
else
OCR1A = nextMainISR;
}
#endif // LIN_ADVANCE
void st_init()
@ -1347,18 +1220,49 @@ void st_init()
// Plan the first interrupt after 8ms from now.
OCR1A = 0x4000;
TCNT1 = 0;
ENABLE_STEPPER_DRIVER_INTERRUPT();
#ifdef LIN_ADVANCE
e_steps = 0;
current_adv_steps = 0;
#ifdef LA_DEBUG_LOGIC
LOGIC_ANALYZER_CH0_ENABLE;
LOGIC_ANALYZER_CH1_ENABLE;
WRITE_NC(LOGIC_ANALYZER_CH0, false);
WRITE_NC(LOGIC_ANALYZER_CH1, false);
#endif
// Initialize state for the linear advance scheduler
nextMainISR = 0;
nextAdvanceISR = ADV_NEVER;
main_Rate = ADV_NEVER;
e_steps = 0;
e_step_loops = 1;
LA_phase = -1;
current_adv_steps = 0;
#endif
enable_endstops(true); // Start with endstops active. After homing they can be disabled
ENABLE_STEPPER_DRIVER_INTERRUPT();
sei();
}
void st_reset_timer()
{
// Clear a possible pending interrupt on OCR1A overflow.
TIFR1 |= 1 << OCF1A;
// Reset the counter.
TCNT1 = 0;
// Wake up after 1ms from now.
OCR1A = 2000;
#ifdef LIN_ADVANCE
nextMainISR = 0;
if(nextAdvanceISR && nextAdvanceISR != ADV_NEVER)
nextAdvanceISR = 0;
#endif
}
// Block until all buffered steps are executed
void st_synchronize()
{
@ -1443,13 +1347,15 @@ void quickStop()
DISABLE_STEPPER_DRIVER_INTERRUPT();
while (blocks_queued()) plan_discard_current_block();
current_block = NULL;
#ifdef LIN_ADVANCE
nextAdvanceISR = ADV_NEVER;
current_adv_steps = 0;
#endif
st_reset_timer();
ENABLE_STEPPER_DRIVER_INTERRUPT();
}
#ifdef BABYSTEPPING
void babystep(const uint8_t axis,const bool direction)
{
//MUST ONLY BE CALLED BY A ISR, it depends on that no other ISR interrupts this
@ -1685,3 +1591,13 @@ void microstep_readings()
#endif
}
#endif //TMC2130
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
void st_reset_fsensor()
{
CRITICAL_SECTION_START;
fsensor_counter = 0;
CRITICAL_SECTION_END;
}
#endif //FILAMENT_SENSOR

View File

@ -37,12 +37,6 @@ void st_init();
void isr();
#ifdef LIN_ADVANCE
void advance_isr();
void advance_isr_scheduler();
void clear_current_adv_vars(); //Used to reset the built up pretension and remaining esteps on filament change.
#endif
// Block until all buffered steps are executed
void st_synchronize();
@ -62,15 +56,7 @@ float st_get_position_mm(uint8_t axis);
// Call this function just before re-enabling the stepper driver interrupt and the global interrupts
// to avoid a stepper timer overflow.
FORCE_INLINE void st_reset_timer()
{
// Clear a possible pending interrupt on OCR1A overflow.
TIFR1 |= 1 << OCF1A;
// Reset the counter.
TCNT1 = 0;
// Wake up after 1ms from now.
OCR1A = 2000;
}
void st_reset_timer();
void checkHitEndstops(); //call from somewhere to create an serial error message with the locations the endstops where hit, in case they were triggered
bool endstops_hit_on_purpose(); //avoid creation of the message, i.e. after homing and before a routine call of checkHitEndstops();
@ -106,7 +92,10 @@ void microstep_readings();
#ifdef BABYSTEPPING
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
// reset the internal filament sensor state
void st_reset_fsensor();
#endif
#endif

View File

@ -11,8 +11,8 @@
#define _millis millis2
#define _micros micros2
#define _delay delay2
#define _tone tone2
#define _noTone noTone2
#define _tone tone
#define _noTone noTone
#define timer02_set_pwm0(pwm0)
@ -20,8 +20,8 @@
#define _millis millis
#define _micros micros
#define _delay delay
#define _tone(x, y) /*tone*/
#define _noTone(x) /*noTone*/
#define _tone tone
#define _noTone noTone
#define timer02_set_pwm0(pwm0)
#endif //SYSTEM_TIMER_2

View File

@ -1403,6 +1403,7 @@ void disable_heater()
target_temperature_bed=0;
soft_pwm_bed=0;
timer02_set_pwm0(soft_pwm_bed << 1);
bedPWMDisabled = 0;
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
//WRITE(HEATER_BED_PIN,LOW);
#endif
@ -2002,6 +2003,8 @@ void check_max_temp()
//! number of repeating the same state with consecutive step() calls
//! used to slow down text switching
struct alert_automaton_mintemp {
const char *m2;
alert_automaton_mintemp(const char *m2):m2(m2){}
private:
enum { ALERT_AUTOMATON_SPEED_DIV = 5 };
enum class States : uint8_t { Init = 0, TempAboveMintemp, ShowPleaseRestart, ShowMintemp };
@ -2021,7 +2024,6 @@ public:
//! @param current_temp current hotend/bed temperature (for computing simple hysteresis)
//! @param mintemp minimal temperature including hysteresis to check current_temp against
void step(float current_temp, float mintemp){
static const char m2[] PROGMEM = "MINTEMP fixed";
static const char m1[] PROGMEM = "Please restart";
switch(state){
case States::Init: // initial state - check hysteresis
@ -2049,8 +2051,9 @@ public:
}
}
};
static alert_automaton_mintemp alert_automaton_hotend, alert_automaton_bed;
static const char m2hotend[] PROGMEM = "MINTEMP HOTEND fixed";
static const char m2bed[] PROGMEM = "MINTEMP BED fixed";
static alert_automaton_mintemp alert_automaton_hotend(m2hotend), alert_automaton_bed(m2bed);
void check_min_temp_heater0()
{

View File

@ -84,6 +84,8 @@ extern int current_voltage_raw_IR;
extern unsigned char soft_pwm_bed;
#endif
extern bool bedPWMDisabled;
#ifdef PIDTEMP
extern int pid_cycle, pid_number_of_cycles;
extern float Kc,_Kp,_Ki,_Kd;

View File

@ -136,14 +136,4 @@ void delay2(unsigned long ms)
}
}
void tone2(__attribute__((unused)) uint8_t _pin, __attribute__((unused)) unsigned int frequency/*, unsigned long duration*/)
{
PIN_SET(BEEPER);
}
void noTone2(__attribute__((unused)) uint8_t _pin)
{
PIN_CLR(BEEPER);
}
#endif //SYSTEM_TIMER_2

View File

@ -23,13 +23,6 @@ extern unsigned long micros2(void);
///! Reimplemented original delay() using timer2
extern void delay2(unsigned long ms);
///! Reimplemented original tone() using timer2
///! Does not perform any PWM tone generation, it just sets the beeper pin to 1
extern void tone2(uint8_t _pin, unsigned int frequency/*, unsigned long duration*/);
///! Turn off beeping - set beeper pin to 0
extern void noTone2(uint8_t _pin);
#if defined(__cplusplus)
}
#endif //defined(__cplusplus)

View File

@ -246,7 +246,9 @@ static void fil_unload_menu();
static void lcd_disable_farm_mode();
static void lcd_set_fan_check();
static void lcd_cutter_enabled();
#ifdef SNMM
static char snmm_stop_print_menu();
#endif //SNMM
#ifdef SDCARD_SORT_ALPHA
static void lcd_sort_type_set();
#endif
@ -948,7 +950,6 @@ static void lcd_status_screen()
}
if (current_click
&& (lcd_commands_type != LcdCommands::StopPrint) //click is aborted unless stop print finishes
&& ( menu_block_entering_on_serious_errors == SERIOUS_ERR_NONE ) // or a serious error blocks entering the menu
)
{
@ -1359,98 +1360,6 @@ void lcd_commands()
#endif // not SNMM
if (lcd_commands_type == LcdCommands::StopPrint) /// stop print
{
if (lcd_commands_step == 0)
{
lcd_commands_step = 6;
}
if (lcd_commands_step == 1 && !blocks_queued())
{
lcd_commands_step = 0;
lcd_commands_type = LcdCommands::Idle;
lcd_setstatuspgm(_T(WELCOME_MSG));
custom_message_type = CustomMsg::Status;
isPrintPaused = false;
}
if (lcd_commands_step == 2 && !blocks_queued())
{
setTargetBed(0);
enquecommand_P(PSTR("M104 S0")); //set hotend temp to 0
manage_heater();
lcd_setstatuspgm(_T(WELCOME_MSG));
cancel_heatup = false;
lcd_commands_step = 1;
}
if (lcd_commands_step == 3 && !blocks_queued())
{
// M84: Disable steppers.
enquecommand_P(PSTR("M84"));
autotempShutdown();
lcd_commands_step = 2;
}
if (lcd_commands_step == 4 && !blocks_queued())
{
lcd_setstatuspgm(_T(MSG_PLEASE_WAIT));
// G90: Absolute positioning.
enquecommand_P(PSTR("G90"));
// M83: Set extruder to relative mode.
enquecommand_P(PSTR("M83"));
#ifdef X_CANCEL_POS
enquecommand_P(PSTR("G1 X" STRINGIFY(X_CANCEL_POS) " Y" STRINGIFY(Y_CANCEL_POS) " E0 F7000"));
#else
enquecommand_P(PSTR("G1 X50 Y" STRINGIFY(Y_MAX_POS) " E0 F7000"));
#endif
lcd_ignore_click(false);
if (mmu_enabled)
lcd_commands_step = 8;
else
lcd_commands_step = 3;
}
if (lcd_commands_step == 5 && !blocks_queued())
{
lcd_setstatuspgm(_T(MSG_PRINT_ABORTED));
// G91: Set to relative positioning.
enquecommand_P(PSTR("G91"));
// Lift up.
enquecommand_P(PSTR("G1 Z15 F1500"));
if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) lcd_commands_step = 4;
else lcd_commands_step = 3;
}
if (lcd_commands_step == 6 && !blocks_queued())
{
lcd_setstatuspgm(_T(MSG_PRINT_ABORTED));
cancel_heatup = true;
setTargetBed(0);
if (mmu_enabled)
setAllTargetHotends(0);
manage_heater();
custom_message_type = CustomMsg::FilamentLoading;
lcd_commands_step = 5;
}
if (lcd_commands_step == 7 && !blocks_queued())
{
if (mmu_enabled)
enquecommand_P(PSTR("M702 C")); //current
else
switch(snmm_stop_print_menu())
{
case 0: enquecommand_P(PSTR("M702")); break;//all
case 1: enquecommand_P(PSTR("M702 U")); break; //used
case 2: enquecommand_P(PSTR("M702 C")); break; //current
default: enquecommand_P(PSTR("M702")); break;
}
lcd_commands_step = 3;
}
if (lcd_commands_step == 8 && !blocks_queued()) { //step 8 is here for delay (going to next step after execution of all gcodes from step 4)
lcd_commands_step = 7;
}
}
if (lcd_commands_type == LcdCommands::FarmModeConfirm) /// farm mode confirm
{
@ -1554,7 +1463,7 @@ void lcd_return_to_status()
//! @brief Pause print, disable nozzle heater, move to park position
void lcd_pause_print()
{
stop_and_save_print_to_ram(0.0,0.0);
stop_and_save_print_to_ram(0.0, -default_retraction);
lcd_return_to_status();
isPrintPaused = true;
if (LcdCommands::Idle == lcd_commands_type)
@ -1776,11 +1685,23 @@ static void lcd_menu_fails_stats_print()
uint8_t crashX = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_X);
uint8_t crashY = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_Y);
lcd_home();
#ifndef PAT9125
lcd_printf_P(failStatsFmt,
_i("Last print failures"), ////c=20 r=1
_i("Power failures"), power, ////c=14 r=1
_i("Filam. runouts"), filam, ////c=14 r=1
_i("Crash"), crashX, crashY); ////c=7 r=1
#else
// On the MK3 include detailed PAT9125 statistics about soft failures
lcd_printf_P(PSTR("%S\n"
" %-16.16S%-3d\n"
" %-7.7S H %-3d S %-3d\n"
" %-7.7S X %-3d Y %-3d"),
_i("Last print failures"), ////c=20 r=1
_i("Power failures"), power, ////c=14 r=1
_i("Runouts"), filam, fsensor_softfail, //c=7 r=1
_i("Crash"), crashX, crashY); ////c=7 r=1
#endif
menu_back_if_clicked_fb();
}
@ -2211,10 +2132,12 @@ void lcd_set_filament_autoload() {
fsensor_autoload_set(!fsensor_autoload_enabled);
}
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
void lcd_set_filament_oq_meass()
{
fsensor_oq_meassure_set(!fsensor_oq_meassure_enabled);
}
#endif
FilamentAction eFilamentAction=FilamentAction::None; // must be initialized as 'non-autoLoad'
@ -2774,9 +2697,9 @@ static void lcd_LoadFilament()
//!
//! @code{.unparsed}
//! |01234567890123456789|
//! |Filament used: | c=18 r=1
//! | 00.00m |
//! |Print time: | c=18 r=1
//! |Filament used: | c=19 r=1
//! | 0000.00m |
//! |Print time: | c=19 r=1
//! | 00h 00m 00s |
//! ----------------------
//! @endcode
@ -2785,32 +2708,33 @@ static void lcd_LoadFilament()
//!
//! @code{.unparsed}
//! |01234567890123456789|
//! |Total filament : | c=18 r=1
//! | 000.00 m |
//! |Total print time : | c=18 r=1
//! | 00d :00h :00 m |
//! |Total filament: | c=19 r=1
//! | 0000.00m |
//! |Total print time: | c=19 r=1
//! | 00d 00h 00m |
//! ----------------------
//! @endcode
//! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations. Translations missing for "d"days, "h"ours, "m"inutes", "s"seconds".
void lcd_menu_statistics()
{
lcd_timeoutToStatus.stop(); //infinite timeout
if (IS_SD_PRINTING)
{
const float _met = ((float)total_filament_used) / (100000.f);
const uint32_t _t = (_millis() - starttime) / 1000ul;
const int _h = _t / 3600;
const int _m = (_t - (_h * 3600ul)) / 60ul;
const int _s = _t - ((_h * 3600ul) + (_m * 60ul));
const uint32_t _h = _t / 3600;
const uint8_t _m = (_t - (_h * 3600ul)) / 60ul;
const uint8_t _s = _t - ((_h * 3600ul) + (_m * 60ul));
lcd_clear();
lcd_home();
lcd_printf_P(_N(
"%S:\n"
"%17.2fm \n"
"%18.2fm \n"
"%S:\n"
"%2dh %02dm %02ds"
"%10ldh %02hhdm %02hhds"
),
_i("Filament used"), _met, ////c=18 r=1
_i("Print time"), _h, _m, _s); ////c=18 r=1
_i("Filament used"), _met, ////c=19 r=1
_i("Print time"), _h, _m, _s); ////c=19 r=1
menu_back_if_clicked_fb();
}
else
@ -2820,29 +2744,20 @@ void lcd_menu_statistics()
uint8_t _hours, _minutes;
uint32_t _days;
float _filament_m = (float)_filament/100;
// int _filament_km = (_filament >= 100000) ? _filament / 100000 : 0;
// if (_filament_km > 0) _filament_m = _filament - (_filament_km * 100000);
_days = _time / 1440;
_hours = (_time - (_days * 1440)) / 60;
_minutes = _time - ((_days * 1440) + (_hours * 60));
lcd_clear();
lcd_home();
lcd_printf_P(_N(
"%S:\n"
"%17.2fm \n"
"%18.2fm \n"
"%S:\n"
"%7ldd :%2hhdh :%02hhdm"
), _i("Total filament"), _filament_m, _i("Total print time"), _days, _hours, _minutes);
KEEPALIVE_STATE(PAUSED_FOR_USER);
while (!lcd_clicked())
{
manage_heater();
manage_inactivity(true);
_delay(100);
}
KEEPALIVE_STATE(NOT_BUSY);
lcd_quick_feedback();
menu_back();
"%10ldd %02hhdh %02hhdm"
),
_i("Total filament"), _filament_m, ////c=19 r=1
_i("Total print time"), _days, _hours, _minutes); ////c=19 r=1
menu_back_if_clicked_fb();
}
}
@ -5936,7 +5851,7 @@ void bowden_menu() {
}
}
//#ifdef SNMM
#ifdef SNMM
static char snmm_stop_print_menu() { //menu for choosing which filaments will be unloaded in stop print
lcd_clear();
@ -5987,6 +5902,8 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be
}
#endif //SNMM
//! @brief Select one of numbered items
//!
//! Create list of items with header. Header can not be selected.
@ -6649,14 +6566,15 @@ static bool fan_error_selftest()
void lcd_resume_print()
{
lcd_return_to_status();
lcd_reset_alert_level();
lcd_setstatuspgm(_T(MSG_RESUMING_PRINT));
lcd_reset_alert_level(); //for fan speed error
if (fan_error_selftest()) return; //abort if error persists
lcd_setstatuspgm(_T(MSG_FINISHING_MOVEMENTS));
st_synchronize();
lcd_setstatuspgm(_T(MSG_RESUMING_PRINT));
isPrintPaused = false;
restore_print_from_ram_and_continue(0.0);
restore_print_from_ram_and_continue(default_retraction);
pause_time += (_millis() - start_pause_print); //accumulate time when print is paused for correct statistics calculation
refresh_cmd_timeout();
SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_RESUMED); //resume octoprint
@ -6795,10 +6713,15 @@ static void lcd_main_menu()
}
if(isPrintPaused && saved_printing_type == PRINTING_TYPE_USB)
{
#ifdef FANCHECK
if((fan_check_error == EFCE_FIXED) && (saved_printing_type == PRINTING_TYPE_USB))
MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
if((fan_check_error == EFCE_FIXED) || (fan_check_error == EFCE_OK))
MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
#else
MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
#endif
}
#ifdef SDSUPPORT
if (card.cardOK || lcd_commands_type == LcdCommands::Layer1Cal)
@ -6967,6 +6890,60 @@ static void lcd_colorprint_change() {
lcd_draw_update = 3;
}
#ifdef LA_LIVE_K
// @wavexx: looks like there's no generic float editing function in menu.cpp so we
// redefine our custom handling functions to mimick other tunables
const char menu_fmt_float13off[] PROGMEM = "%c%-13.13S%6.6S";
static void lcd_advance_draw_K(char chr, float val)
{
if (val <= 0)
lcd_printf_P(menu_fmt_float13off, chr, MSG_ADVANCE_K, _T(MSG_OFF));
else
lcd_printf_P(menu_fmt_float13, chr, MSG_ADVANCE_K, val);
}
static void lcd_advance_edit_K(void)
{
if (lcd_draw_update)
{
if (lcd_encoder < 0) lcd_encoder = 0;
if (lcd_encoder > 999) lcd_encoder = 999;
lcd_set_cursor(0, 1);
lcd_advance_draw_K(' ', 0.01 * lcd_encoder);
}
if (LCD_CLICKED)
{
extruder_advance_K = 0.01 * lcd_encoder;
menu_back_no_reset();
}
}
static uint8_t lcd_advance_K()
{
if (menu_item == menu_line)
{
if (lcd_draw_update)
{
lcd_set_cursor(0, menu_row);
lcd_advance_draw_K((lcd_encoder == menu_item)?'>':' ', extruder_advance_K);
}
if (menu_clicked && (lcd_encoder == menu_item))
{
menu_submenu_no_reset(lcd_advance_edit_K);
lcd_encoder = 100. * extruder_advance_K;
return menu_item_ret();
}
}
menu_item++;
return 0;
}
#define MENU_ITEM_EDIT_advance_K() do { if (lcd_advance_K()) return; } while (0)
#endif
static void lcd_tune_menu()
{
typedef struct
@ -7005,8 +6982,11 @@ static void lcd_tune_menu()
MENU_ITEM_EDIT_int3_P(_T(MSG_FAN_SPEED), &fanSpeed, 0, 255);//5
MENU_ITEM_EDIT_int3_P(_i("Flow"), &extrudemultiply, 10, 999);//6////MSG_FLOW
#ifdef LA_LIVE_K
MENU_ITEM_EDIT_advance_K();//7
#endif
#ifdef FILAMENTCHANGEENABLE
MENU_ITEM_FUNCTION_P(_T(MSG_FILAMENTCHANGE), lcd_colorprint_change);//7
MENU_ITEM_FUNCTION_P(_T(MSG_FILAMENTCHANGE), lcd_colorprint_change);//8
#endif
#ifdef FILAMENT_SENSOR
@ -7205,7 +7185,6 @@ void lcd_print_stop()
// Clear any saved printing state
cancel_saved_printing();
cancel_heatup = true;
// Abort the planner/queue/sd
planner_abort_hard();
@ -7216,19 +7195,48 @@ void lcd_print_stop()
CRITICAL_SECTION_END;
#ifdef MESH_BED_LEVELING
mbl.active = false; //also prevents undoing the mbl compensation a second time in the second planner_abort_hard()
#endif
lcd_setstatuspgm(_T(MSG_PRINT_ABORTED));
stoptime = _millis();
unsigned long t = (stoptime - starttime - pause_time) / 1000; //time in s
pause_time = 0;
save_statistics(total_filament_used, t);
lcd_return_to_status();
lcd_ignore_click(true);
lcd_commands_step = 0;
lcd_commands_type = LcdCommands::StopPrint;
// Turn off the print fan
SET_OUTPUT(FAN_PIN);
WRITE(FAN_PIN, 0);
fanSpeed = 0;
lcd_commands_step = 0;
lcd_commands_type = LcdCommands::Idle;
lcd_cooldown(); //turns off heaters and fan; goes to status screen.
cancel_heatup = true; //unroll temperature wait loop stack.
current_position[Z_AXIS] += 10; //lift Z.
plan_buffer_line_curposXYZE(manual_feedrate[Z_AXIS] / 60, active_extruder);
if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) //if axis are homed, move to parked position.
{
current_position[X_AXIS] = X_CANCEL_POS;
current_position[Y_AXIS] = Y_CANCEL_POS;
plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
}
st_synchronize();
if (mmu_enabled) extr_unload(); //M702 C
finishAndDisableSteppers(); //M84
lcd_setstatuspgm(_T(WELCOME_MSG));
custom_message_type = CustomMsg::Status;
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;
isPrintPaused = false; //clear isPrintPaused flag to allow starting next print after pause->stop scenario.
}
void lcd_sdcard_stop()
@ -7420,26 +7428,24 @@ bool lcd_selftest()
int _progress = 0;
bool _result = true;
bool _swapped_fan = false;
#if IR_SENSOR_ANALOG
bool bAction;
bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true);
if(!bAction)
return(false);
#endif //IR_SENSOR_ANALOG
lcd_wait_for_cool_down();
lcd_clear();
lcd_set_cursor(0, 0); lcd_puts_P(_i("Self test start "));////MSG_SELFTEST_START c=20
#ifdef TMC2130
FORCE_HIGH_POWER_START;
#endif // TMC2130
#if !IR_SENSOR_ANALOG
_delay(2000);
#endif //!IR_SENSOR_ANALOG
FORCE_BL_ON_START;
_delay(2000);
KEEPALIVE_STATE(IN_HANDLER);
#if IR_SENSOR_ANALOG
bool bAction;
bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament unloaded?"),false,true);
if(!bAction)
return(false);
#endif //IR_SENSOR_ANALOG
_progress = lcd_selftest_screen(TestScreen::ExtruderFan, _progress, 3, true, 2000);
#if (defined(FANCHECK) && defined(TACH_0))

View File

@ -504,7 +504,7 @@
#define MMU_REQUIRED_FW_BUILDNR 132
#define MMU_FORCE_STEALTH_MODE
#define MMU_DEBUG //print communication between MMU2 and printer on serial
//#define MMU_HAS_CUTTER
#define MMU_HAS_CUTTER
#define MMU_IDLER_SENSOR_ATTEMPTS_NR 21 //max. number of attempts to load filament if first load failed; value for max bowden length and case when loading fails right at the beginning

View File

@ -505,7 +505,7 @@
#define MMU_REQUIRED_FW_BUILDNR 132
#define MMU_FORCE_STEALTH_MODE
#define MMU_DEBUG //print communication between MMU2 and printer on serial
//#define MMU_HAS_CUTTER
#define MMU_HAS_CUTTER
#define MMU_IDLER_SENSOR_ATTEMPTS_NR 21 //max. number of attempts to load filament if first load failed; value for max bowden length and case when loading fails right at the beginning

View File

@ -504,7 +504,7 @@
#define MMU_REQUIRED_FW_BUILDNR 132
#define MMU_FORCE_STEALTH_MODE
#define MMU_DEBUG //print communication between MMU2 and printer on serial
//#define MMU_HAS_CUTTER
#define MMU_HAS_CUTTER
// This is experimental feature requested by our test department.
// There is no known use for ordinary user. If enabled by this macro

View File

@ -505,7 +505,7 @@
#define MMU_REQUIRED_FW_BUILDNR 132
#define MMU_FORCE_STEALTH_MODE
#define MMU_DEBUG //print communication between MMU2 and printer on serial
//#define MMU_HAS_CUTTER
#define MMU_HAS_CUTTER
// This is experimental feature requested by our test department.
// There is no known use for ordinary user. If enabled by this macro

View File

@ -151,8 +151,8 @@
// this value is litlebit higher that real limit, because ambient termistor is on the board and is temperated from it,
// temperature inside the case is around 31C for ambient temperature 25C, when the printer is powered on long time and idle
// the real limit is 15C (same as MINTEMP limit), this is because 15C is end of scale for both used thermistors (bed, heater)
#define MINTEMP_MINAMBIENT 25
#define MINTEMP_MINAMBIENT_RAW 978
#define MINTEMP_MINAMBIENT 10
#define MINTEMP_MINAMBIENT_RAW 1002
#define DEBUG_DCODE3
@ -282,14 +282,14 @@
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_0_MINTEMP 10
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define HEATER_MINTEMP_DELAY 15000 // [ms] ! if changed, check maximal allowed value @ ShortTimer
#if HEATER_MINTEMP_DELAY>USHRT_MAX
#error "Check maximal allowed value @ ShortTimer (see HEATER_MINTEMP_DELAY definition)"
#endif
#define BED_MINTEMP 15
#define BED_MINTEMP 10
#define BED_MINTEMP_DELAY 50000 // [ms] ! if changed, check maximal allowed value @ ShortTimer
#if BED_MINTEMP_DELAY>USHRT_MAX
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
@ -618,6 +618,10 @@
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
//#define UVLO_Z_AXIS_SHIFT 1.92
#define UVLO_Z_AXIS_SHIFT 0.64
// When powered off during PP recovery, the Z axis position can still be re-adjusted. In this case
// we just need to shift to the nearest fullstep, but we need a move which is at least
// "dropsegments" steps long. All the above rules still need to apply.
#define UVLO_TINY_Z_AXIS_SHIFT 0.16
// If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically.
#define AUTOMATIC_UVLO_BED_TEMP_OFFSET 5
@ -630,7 +634,7 @@
#define MMU_REQUIRED_FW_BUILDNR 83
#define MMU_HWRESET
#define MMU_DEBUG //print communication between MMU2 and printer on serial
//#define MMU_HAS_CUTTER
#define MMU_HAS_CUTTER
#define MMU_IDLER_SENSOR_ATTEMPTS_NR 21 //max. number of attempts to load filament if first load failed; value for max bowden length and case when loading fails right at the beginning
#endif //__CONFIGURATION_PRUSA_H

View File

@ -153,8 +153,8 @@
// this value is litlebit higher that real limit, because ambient termistor is on the board and is temperated from it,
// temperature inside the case is around 31C for ambient temperature 25C, when the printer is powered on long time and idle
// the real limit is 15C (same as MINTEMP limit), this is because 15C is end of scale for both used thermistors (bed, heater)
#define MINTEMP_MINAMBIENT 25
#define MINTEMP_MINAMBIENT_RAW 978
#define MINTEMP_MINAMBIENT 10
#define MINTEMP_MINAMBIENT_RAW 1002
#define DEBUG_DCODE3
@ -284,14 +284,14 @@
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_0_MINTEMP 10
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define HEATER_MINTEMP_DELAY 15000 // [ms] ! if changed, check maximal allowed value @ ShortTimer
#if HEATER_MINTEMP_DELAY>USHRT_MAX
#error "Check maximal allowed value @ ShortTimer (see HEATER_MINTEMP_DELAY definition)"
#endif
#define BED_MINTEMP 15
#define BED_MINTEMP 10
#define BED_MINTEMP_DELAY 50000 // [ms] ! if changed, check maximal allowed value @ ShortTimer
#if BED_MINTEMP_DELAY>USHRT_MAX
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
@ -620,7 +620,11 @@
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
//#define UVLO_Z_AXIS_SHIFT 1.92
#define UVLO_Z_AXIS_SHIFT 0.64
// If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically.
// When powered off during PP recovery, the Z axis position can still be re-adjusted. In this case
// we just need to shift to the nearest fullstep, but we need a move which is at least
// "dropsegments" steps long. All the above rules still need to apply.
#define UVLO_TINY_Z_AXIS_SHIFT 0.16
// If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically.
#define AUTOMATIC_UVLO_BED_TEMP_OFFSET 5
#define HEATBED_V2
@ -632,7 +636,7 @@
#define MMU_REQUIRED_FW_BUILDNR 83
#define MMU_HWRESET
#define MMU_DEBUG //print communication between MMU2 and printer on serial
//#define MMU_HAS_CUTTER
#define MMU_HAS_CUTTER
// This is experimental feature requested by our test department.
// There is no known use for ordinary user. If enabled by this macro

View File

@ -56,7 +56,7 @@
# Some may argue that this is only used by a script, BUT as soon someone accidentally or on purpose starts Arduino IDE
# it will use the default Arduino IDE folders and so can corrupt the build environment.
#
# Version: 1.0.6-Build_10
# Version: 1.0.6-Build_13
# Change log:
# 12 Jan 2019, 3d-gussner, Fixed "compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections" in 'platform.txt'
# 16 Jan 2019, 3d-gussner, Build_2, Added development check to modify 'Configuration.h' to prevent unwanted LCD messages that Firmware is unknown
@ -114,7 +114,10 @@
# 26 Jul 2019, 3d-gussner, Change JSON repository to prusa3d after PR https://github.com/prusa3d/Arduino_Boards/pull/1 was merged
# 23 Sep 2019, 3d-gussner, Prepare PF-build.sh for comming Prusa3d/Arduino_Boards version 1.0.2 Pull Request
# 17 Oct 2019, 3d-gussner, Changed folder and check file names to have seperated build enviroments depening on Arduino IDE version and
# board-versions.
# board-versions.
# 15 Dec 2019, 3d-gussner, Prepare for switch to Prusa3d/PF-build-env repository
# 15 Dec 2019, 3d-gussner, Fix Audrino user preferences for the chosen board.
# 17 Dec 2019, 3d-gussner, Fix "timer0_fract = 0" warning by using Arduino_boards v1.0.3
#### Start check if OSTYPE is supported
OS_FOUND=$( command -v uname)
@ -207,19 +210,22 @@ if ! type python > /dev/null; then
fi
fi
#### End prepare bash environment
#### End prepare bash / Linux environment
#### Set build environment
ARDUINO_ENV="1.8.5"
BUILD_ENV="1.0.6"
BOARD="rambo"
BOARD_PACKAGE_NAME="PrusaResearchRambo"
BOARD_VERSION="1.0.1"
BOARD="prusa_einsy_rambo"
BOARD_PACKAGE_NAME="PrusaResearch"
BOARD_VERSION="1.0.3"
#BOARD_URL="https://raw.githubusercontent.com/3d-gussner/Arduino_Boards/Prusa_Merge_v1.0.3/IDE_Board_Manager/package_prusa3d_index.json"
BOARD_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json"
BOARD_FILENAME="prusa3drambo"
BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3drambo-1.0.1.tar.bz2"
PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env/releases/download/$BUILD_ENV/PF-build-env-$BUILD_ENV.zip"
BOARD_FILENAME="prusa3dboards"
#BOARD_FILE_URL="https://raw.githubusercontent.com/3d-gussner/Arduino_Boards/Prusa_Merge_v1.0.3/IDE_Board_Manager/prusa3dboards-1.0.3.tar.bz2"
BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3dboards-1.0.3.tar.bz2"
#PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env-1/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip"
PF_BUILD_FILE_URL="https://github.com/prusa3d/PF-build-env/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip"
LIB="PrusaLibrary"
SCRIPT_PATH="$( cd "$(dirname "$0")" ; pwd -P )"
@ -233,6 +239,7 @@ echo "Ardunio IDE :" $ARDUINO_ENV
echo "Build env :" $BUILD_ENV
echo "Board :" $BOARD
echo "Package name:" $BOARD_PACKAGE_NAME
echo "Board v. :" $BOARD_VERSION
echo "Specific Lib:" $LIB
echo ""
@ -321,7 +328,7 @@ if [ ! -e ../PF-build-env-$BUILD_ENV/Preferences-$ARDUINO_ENV-$BOARD_VERSION-$TA
echo "update.check"
sed -i 's/update.check = true/update.check = false/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
echo "board"
sed -i 's/board = uno/board = $BOARD/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
sed -i "s/board = uno/board = $BOARD/g" ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
echo "editor.linenumbers"
sed -i 's/editor.linenumbers = false/editor.linenumbers = true/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
echo "boardsmanager.additional.urls"
@ -364,7 +371,7 @@ if [[ ! -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$P
fi
# Download and extract Prusa Firmware specific library files
if [ ! -f "PF-build-env-$BUILD_ENV.zip" ]; then
if [ ! -f "PF-build-env-WinLin-$BUILD_ENV.zip" ]; then
echo "$(tput setaf 6)Downloading Prusa Firmware build environment...$(tput setaf 2)"
sleep 2
wget $PF_BUILD_FILE_URL || exit 11
@ -373,7 +380,7 @@ fi
if [ ! -e "../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]; then
echo "$(tput setaf 6)Unzipping Prusa Firmware build environment...$(tput setaf 2)"
sleep 2
unzip -o PF-build-env-$BUILD_ENV.zip -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 12
unzip -o PF-build-env-WinLin-$BUILD_ENV.zip -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 12
echo "# PF-build-env-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor-$BUILD_ENV" >> ../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
echo "$(tput sgr0)"
fi

View File

@ -46,7 +46,7 @@ _Note: Multi language build is not supported._
* Open Arduino and navigate to File -> Preferences -> Settings
* To the text field `"Additional Boards Manager URLSs"` add `https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json`
* Open Board manager (`Tools->Board->Board manager`), and install `Prusa Research AVR MK3 RAMBo EINSy board`
* Open Board manager (`Tools->Board->Board manager`), and install `Prusa Research AVR Boards by Prusa Research`
**c.** Modify compiler flags in `platform.txt` file

View File

@ -1,5 +1,5 @@
#!/bin/bash
BUILD_ENV="1.0.6"
BUILD_ENV="1.0.6.1"
SCRIPT_PATH="$( cd "$(dirname "$0")" ; pwd -P )"
if [ ! -d "build-env" ]; then
@ -8,7 +8,8 @@ fi
cd build-env || exit 2
if [ ! -f "PF-build-env-Linux64-$BUILD_ENV.zip" ]; then
wget https://github.com/mkbel/PF-build-env/releases/download/$BUILD_ENV/PF-build-env-Linux64-$BUILD_ENV.zip || exit 3
#wget https://github.com/3d-gussner/PF-build-env-1/releases/download/$BUILD_ENV-Linux64/PF-build-env-Linux64-$BUILD_ENV.zip || exit 3
wget https://github.com/prusa3d/PF-build-env/releases/download/$BUILD_ENV-Linux64/PF-build-env-Linux64-$BUILD_ENV.zip || exit 3
fi
if [ ! -d "../../PF-build-env-$BUILD_ENV" ]; then