Merge pull request #288 from PavelSindler/MK3_for_merging
Merging MK3 from dev repository
This commit is contained in:
commit
9c7a4e4882
77 changed files with 41898 additions and 13720 deletions
|
@ -4,20 +4,27 @@
|
|||
#include "boards.h"
|
||||
#include "Configuration_prusa.h"
|
||||
|
||||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
||||
// Firmware version
|
||||
#define FW_version "3.0.5"
|
||||
#define FW_version "3.1.1-RC1"
|
||||
#define FW_build 121
|
||||
//#define FW_build --BUILD-NUMBER--
|
||||
#define FW_version_build FW_version " b" STR(FW_build)
|
||||
|
||||
|
||||
#define FW_PRUSA3D_MAGIC "PRUSA3DFW"
|
||||
#define FW_PRUSA3D_MAGIC_LEN 10
|
||||
|
||||
// The total size of the EEPROM is
|
||||
// 4096 for the Atmega2560
|
||||
#define EEPROM_TOP 4096
|
||||
#define EEPROM_SILENT 4095
|
||||
#define EEPROM_LANG 4094
|
||||
#define EEPROM_BABYSTEP_X 4092
|
||||
#define EEPROM_BABYSTEP_Y 4090
|
||||
#define EEPROM_BABYSTEP_Z 4088
|
||||
#define EEPROM_BABYSTEP_Z_SET 4087
|
||||
#define EEPROM_CALIBRATION_STATUS 4087
|
||||
#define EEPROM_BABYSTEP_Z0 4085
|
||||
#define EEPROM_FILAMENTUSED 4081
|
||||
// uint32_t
|
||||
|
@ -30,17 +37,92 @@
|
|||
// Offsets of the Z heiths of the calibration points from the first point.
|
||||
// The offsets are saved as 16bit signed int, scaled to tenths of microns.
|
||||
#define EEPROM_BED_CALIBRATION_Z_JITTER (EEPROM_BED_CALIBRATION_VEC_Y-2*8)
|
||||
#define EEPROM_FARM_MODE (EEPROM_BED_CALIBRATION_Z_JITTER-1)
|
||||
#define EEPROM_FARM_NUMBER (EEPROM_FARM_MODE-3)
|
||||
|
||||
#define EEPROM_FARM_MODE (EEPROM_BED_CALIBRATION_Z_JITTER-4)
|
||||
// Correction of the bed leveling, in micrometers.
|
||||
// Maximum 50 micrometers allowed.
|
||||
// Bed correction is valid if set to 1. If set to zero or 255, the successive 4 bytes are invalid.
|
||||
#define EEPROM_BED_CORRECTION_VALID (EEPROM_FARM_NUMBER-1)
|
||||
#define EEPROM_BED_CORRECTION_LEFT (EEPROM_BED_CORRECTION_VALID-1)
|
||||
#define EEPROM_BED_CORRECTION_RIGHT (EEPROM_BED_CORRECTION_LEFT-1)
|
||||
#define EEPROM_BED_CORRECTION_FRONT (EEPROM_BED_CORRECTION_RIGHT-1)
|
||||
#define EEPROM_BED_CORRECTION_REAR (EEPROM_BED_CORRECTION_FRONT-1)
|
||||
#define EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY (EEPROM_BED_CORRECTION_REAR-1)
|
||||
#define EEPROM_PRINT_FLAG (EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY-1)
|
||||
#define EEPROM_PROBE_TEMP_SHIFT (EEPROM_PRINT_FLAG - 2*5) //5 x int for storing pinda probe temp shift relative to 50 C; unit: motor steps
|
||||
#define EEPROM_TEMP_CAL_ACTIVE (EEPROM_PROBE_TEMP_SHIFT - 1)
|
||||
#define EEPROM_BOWDEN_LENGTH (EEPROM_TEMP_CAL_ACTIVE - 2*4) //4 x int for bowden lengths for multimaterial
|
||||
#define EEPROM_CALIBRATION_STATUS_PINDA (EEPROM_BOWDEN_LENGTH - 1) //0 - not calibrated; 1 - calibrated
|
||||
#define EEPROM_UVLO (EEPROM_CALIBRATION_STATUS_PINDA - 1) //1 - uvlo during print
|
||||
#define EEPROM_UVLO_CURRENT_POSITION (EEPROM_UVLO-2*4) // 2 x float for current_position in X and Y axes
|
||||
#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_FEEDRATE (EEPROM_UVLO_TARGET_BED - 2)
|
||||
#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_E_ABS (EEPROM_UVLO_Z_MICROSTEPS - 1)
|
||||
#define EEPROM_UVLO_CURRENT_POSITION_E (EEPROM_UVLO_E_ABS - 4) //float for current position in E
|
||||
|
||||
// Crash detection mode EEPROM setting
|
||||
#define EEPROM_CRASH_DET (EEPROM_UVLO_MESH_BED_LEVELING-12)
|
||||
// Filament sensor on/off EEPROM setting
|
||||
#define EEPROM_FSENSOR (EEPROM_UVLO_MESH_BED_LEVELING-14)
|
||||
// Crash detection counter
|
||||
#define EEPROM_CRASH_COUNT (EEPROM_UVLO_MESH_BED_LEVELING-15)
|
||||
// Filament runout/error coutner
|
||||
#define EEPROM_FERROR_COUNT (EEPROM_UVLO_MESH_BED_LEVELING-16)
|
||||
// Power loss errors
|
||||
#define EEPROM_POWER_COUNT (EEPROM_UVLO_MESH_BED_LEVELING-17)
|
||||
#define EEPROM_DIR_DEPTH (EEPROM_POWER_COUNT-1)
|
||||
#define EEPROM_DIRS (EEPROM_DIR_DEPTH-80) //8 chars for each dir name, max 10 levels
|
||||
|
||||
//TMC2130 configuration
|
||||
#define EEPROM_TMC_AXIS_SIZE //axis configuration block size
|
||||
#define EEPROM_TMC_X (EEPROM_TMC + 0 * EEPROM_TMC_AXIS_SIZE) //X axis configuration blok
|
||||
#define EEPROM_TMC_Y (EEPROM_TMC + 1 * EEPROM_TMC_AXIS_SIZE) //Y axis
|
||||
#define EEPROM_TMC_Z (EEPROM_TMC + 2 * EEPROM_TMC_AXIS_SIZE) //Z axis
|
||||
#define EEPROM_TMC_E (EEPROM_TMC + 3 * EEPROM_TMC_AXIS_SIZE) //E axis
|
||||
//TMC2130 - X axis
|
||||
#define EEPROM_TMC_X_USTEPS_INTPOL (EEPROM_TMC_X + 0) // 1byte, bit 0..4 USTEPS, bit 7 INTPOL
|
||||
#define EEPROM_TMC_X_PWM_AMPL (EEPROM_TMC_X + 1) // 1byte (0..255)
|
||||
#define EEPROM_TMC_X_PWM_GRAD_FREQ (EEPROM_TMC_X + 2) // 1byte, bit 0..3 GRAD, bit 4..5 FREQ
|
||||
#define EEPROM_TMC_X_TCOOLTHRS (EEPROM_TMC_X + 3) // 2bytes (0..)
|
||||
#define EEPROM_TMC_X_SG_THRS (EEPROM_TMC_X + 5) // 1byte, (-64..+63)
|
||||
#define EEPROM_TMC_X_CURRENT_H (EEPROM_TMC_X + 6) // 1byte, (0..63)
|
||||
#define EEPROM_TMC_X_CURRENT_R (EEPROM_TMC_X + 7) // 1byte, (0..63)
|
||||
#define EEPROM_TMC_X_HOME_SG_THRS (EEPROM_TMC_X + 8) // 1byte, (-64..+63)
|
||||
#define EEPROM_TMC_X_HOME_CURRENT_R (EEPROM_TMC_X + 9) // 1byte, (-64..+63)
|
||||
#define EEPROM_TMC_X_HOME_DTCOOLTHRS (EEPROM_TMC_X + 10) // 1byte (-128..+127)
|
||||
#define EEPROM_TMC_X_DTCOOLTHRS_LOW (EEPROM_TMC_X + 11) // 1byte (-128..+127)
|
||||
#define EEPROM_TMC_X_DTCOOLTHRS_HIGH (EEPROM_TMC_X + 12) // 1byte (-128..+127)
|
||||
#define EEPROM_TMC_X_SG_THRS_LOW (EEPROM_TMC_X + 13) // 1byte, (-64..+63)
|
||||
#define EEPROM_TMC_X_SG_THRS_HIGH (EEPROM_TMC_X + 14) // 1byte, (-64..+63)
|
||||
|
||||
#define EEPROM_XYZ_CAL_SKEW (EEPROM_POWER_COUNT - 4) //float for skew backup
|
||||
|
||||
#define EEPROM_WIZARD_ACTIVE (EEPROM_XYZ_CAL_SKEW - 1)
|
||||
|
||||
#define EEPROM_BELTSTATUS_X (EEPROM_WIZARD_ACTIVE - 2) //uint16
|
||||
#define EEPROM_BELTSTATUS_Y (EEPROM_BELTSTATUS_X - 2) //uint16
|
||||
|
||||
// Currently running firmware, each digit stored as uint16_t.
|
||||
// The flavor differentiates a dev, alpha, beta, release candidate or a release version.
|
||||
#define EEPROM_FIRMWARE_VERSION_END (FW_PRUSA3D_MAGIC_LEN+8)
|
||||
#define EEPROM_FIRMWARE_VERSION_FLAVOR (FW_PRUSA3D_MAGIC_LEN+6)
|
||||
#define EEPROM_FIRMWARE_VERSION_REVISION (FW_PRUSA3D_MAGIC_LEN+4)
|
||||
#define EEPROM_FIRMWARE_VERSION_MINOR (FW_PRUSA3D_MAGIC_LEN+2)
|
||||
#define EEPROM_FIRMWARE_VERSION_MAJOR FW_PRUSA3D_MAGIC_LEN
|
||||
// Magic string, indicating that the current or the previous firmware running was the Prusa3D firmware.
|
||||
#define EEPROM_FIRMWARE_PRUSA_MAGIC
|
||||
#define EEPROM_FIRMWARE_PRUSA_MAGIC 0
|
||||
|
||||
#define EEPROM_OFFSET 20 //offset for storing settings using M500
|
||||
//#define EEPROM_OFFSET
|
||||
|
||||
// This configuration file contains the basic settings.
|
||||
// Advanced settings can be found in Configuration_adv.h
|
||||
|
@ -154,6 +236,10 @@
|
|||
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
|
||||
#define PREVENT_LENGTHY_EXTRUDE
|
||||
|
||||
#ifdef DEBUG_DISABLE_PREVENT_EXTRUDER
|
||||
#undef PREVENT_DANGEROUS_EXTRUDE
|
||||
#undef PREVENT_LENGTHY_EXTRUDE
|
||||
#endif //DEBUG_DISABLE_PREVENT_EXTRUDER
|
||||
|
||||
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
|
||||
|
||||
|
@ -226,8 +312,8 @@ your extruder heater takes 2 minutes to hit the target on heating.
|
|||
|
||||
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
||||
|
||||
const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||
//#define DISABLE_MAX_ENDSTOPS
|
||||
//#define DISABLE_MIN_ENDSTOPS
|
||||
|
@ -250,10 +336,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
#define DISABLE_E false // For all extruders
|
||||
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
|
||||
|
||||
#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
|
||||
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
|
||||
#define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false
|
||||
#define INVERT_Z_DIR false // for Mendel set to false, for Orca set to true
|
||||
#define INVERT_E0_DIR true // for direct drive extruder v9 set to true, for geared extruder set to false
|
||||
#define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true
|
||||
#define INVERT_E0_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
|
||||
#define INVERT_E1_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
|
||||
#define INVERT_E2_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
|
||||
|
||||
|
@ -263,15 +349,21 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
#define Y_HOME_DIR -1
|
||||
#define Z_HOME_DIR -1
|
||||
|
||||
#ifdef DEBUG_DISABLE_SWLIMITS
|
||||
#define min_software_endstops false
|
||||
#define max_software_endstops false
|
||||
#else
|
||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
||||
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
||||
|
||||
#endif //DEBUG_DISABLE_SWLIMITS
|
||||
|
||||
|
||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||
|
||||
#define Z_HEIGHT_HIDE_LIVE_ADJUST_MENU 2.0f
|
||||
|
||||
//============================= Bed Auto Leveling ===========================
|
||||
|
||||
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
|
||||
|
@ -405,9 +497,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
// #define EXTRUDER_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
|
||||
|
||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||
#define DEFAULT_XYJERK 20.0 // (mm/sec)
|
||||
#define DEFAULT_XJERK 15 // (mm/sec)
|
||||
#define DEFAULT_YJERK 15 // (mm/sec)
|
||||
#define DEFAULT_ZJERK 0.4 // (mm/sec)
|
||||
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
||||
#define DEFAULT_EJERK 2.5 // (mm/sec)
|
||||
|
||||
//===========================================================================
|
||||
//=============================Additional Features===========================
|
||||
|
@ -433,7 +526,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
// please keep turned on if you can.
|
||||
//#define EEPROM_CHITCHAT
|
||||
|
||||
|
||||
// Host Keepalive
|
||||
//
|
||||
// When enabled Marlin will send a busy status message to the host
|
||||
// every couple of seconds when it can't accept commands.
|
||||
//
|
||||
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
|
||||
#define HOST_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
|
||||
|
||||
//LCD and SD support
|
||||
#define ULTRA_LCD //general LCD support, also 16x2
|
||||
|
@ -678,14 +777,36 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||
//#define FILAMENT_LCD_DISPLAY
|
||||
|
||||
|
||||
// Calibration status of the machine, to be stored into the EEPROM,
|
||||
// (unsigned char*)EEPROM_CALIBRATION_STATUS
|
||||
enum CalibrationStatus
|
||||
{
|
||||
// Freshly assembled, needs to peform a self-test and the XYZ calibration.
|
||||
CALIBRATION_STATUS_ASSEMBLED = 255,
|
||||
|
||||
// For the wizard: self test has been performed, now the XYZ calibration is needed.
|
||||
CALIBRATION_STATUS_XYZ_CALIBRATION = 250,
|
||||
|
||||
// For the wizard: factory assembled, needs to run Z calibration.
|
||||
CALIBRATION_STATUS_Z_CALIBRATION = 240,
|
||||
|
||||
// The XYZ calibration has been performed, now it remains to run the V2Calibration.gcode.
|
||||
CALIBRATION_STATUS_LIVE_ADJUST = 230,
|
||||
|
||||
// Calibrated, ready to print.
|
||||
CALIBRATION_STATUS_CALIBRATED = 1,
|
||||
|
||||
// Legacy: resetted by issuing a G86 G-code.
|
||||
// This value can only be expected after an upgrade from the initial MK2 firmware releases.
|
||||
// Currently the G86 sets the calibration status to
|
||||
CALIBRATION_STATUS_UNKNOWN = 0,
|
||||
};
|
||||
|
||||
#include "Configuration_adv.h"
|
||||
#include "thermistortables.h"
|
||||
|
||||
#define PINDA_THERMISTOR
|
||||
|
||||
|
||||
#define AMBIENT_THERMISTOR
|
||||
|
||||
#endif //__CONFIGURATION_H
|
||||
|
|
|
@ -11,12 +11,22 @@
|
|||
|
||||
void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size)
|
||||
{
|
||||
do
|
||||
{
|
||||
eeprom_write_byte((unsigned char*)pos, *value);
|
||||
pos++;
|
||||
value++;
|
||||
}while(--size);
|
||||
while (size--) {
|
||||
uint8_t * const p = (uint8_t * const)pos;
|
||||
uint8_t v = *value;
|
||||
// EEPROM has only ~100,000 write cycles,
|
||||
// so only write bytes that have changed!
|
||||
if (v != eeprom_read_byte(p)) {
|
||||
eeprom_write_byte(p, v);
|
||||
if (eeprom_read_byte(p) != v) {
|
||||
SERIAL_ECHOLNPGM("EEPROM Error");
|
||||
return;
|
||||
}
|
||||
}
|
||||
pos++;
|
||||
value++;
|
||||
};
|
||||
|
||||
}
|
||||
#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value))
|
||||
void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size)
|
||||
|
@ -30,26 +40,20 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size)
|
|||
}
|
||||
#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value))
|
||||
//======================================================================================
|
||||
|
||||
|
||||
|
||||
|
||||
#define EEPROM_OFFSET 100
|
||||
|
||||
|
||||
#define EEPROM_OFFSET 20
|
||||
// IMPORTANT: Whenever there are changes made to the variables stored in EEPROM
|
||||
// in the functions below, also increment the version number. This makes sure that
|
||||
// the default values are used whenever there is a change to the data, to prevent
|
||||
// wrong data being written to the variables.
|
||||
// ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
|
||||
|
||||
#define EEPROM_VERSION "V13"
|
||||
#define EEPROM_VERSION "V1"
|
||||
|
||||
#ifdef EEPROM_SETTINGS
|
||||
void Config_StoreSettings()
|
||||
void Config_StoreSettings(uint16_t offset, uint8_t level)
|
||||
{
|
||||
char ver[4]= "000";
|
||||
int i=EEPROM_OFFSET;
|
||||
int i = offset;
|
||||
EEPROM_WRITE_VAR(i,ver); // invalidate data first
|
||||
EEPROM_WRITE_VAR(i,axis_steps_per_unit);
|
||||
EEPROM_WRITE_VAR(i,max_feedrate);
|
||||
|
@ -59,9 +63,10 @@ void Config_StoreSettings()
|
|||
EEPROM_WRITE_VAR(i,minimumfeedrate);
|
||||
EEPROM_WRITE_VAR(i,mintravelfeedrate);
|
||||
EEPROM_WRITE_VAR(i,minsegmenttime);
|
||||
EEPROM_WRITE_VAR(i,max_xy_jerk);
|
||||
EEPROM_WRITE_VAR(i,max_z_jerk);
|
||||
EEPROM_WRITE_VAR(i,max_e_jerk);
|
||||
EEPROM_WRITE_VAR(i,max_jerk[X_AXIS]);
|
||||
EEPROM_WRITE_VAR(i,max_jerk[Y_AXIS]);
|
||||
EEPROM_WRITE_VAR(i,max_jerk[Z_AXIS]);
|
||||
EEPROM_WRITE_VAR(i,max_jerk[E_AXIS]);
|
||||
EEPROM_WRITE_VAR(i,add_homing);
|
||||
#ifndef ULTIPANEL
|
||||
int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED;
|
||||
|
@ -70,12 +75,13 @@ void Config_StoreSettings()
|
|||
|
||||
|
||||
#endif
|
||||
EEPROM_WRITE_VAR(i,plaPreheatHotendTemp);
|
||||
/* EEPROM_WRITE_VAR(i,plaPreheatHotendTemp);
|
||||
EEPROM_WRITE_VAR(i,plaPreheatHPBTemp);
|
||||
EEPROM_WRITE_VAR(i,plaPreheatFanSpeed);
|
||||
EEPROM_WRITE_VAR(i,absPreheatHotendTemp);
|
||||
EEPROM_WRITE_VAR(i,absPreheatHPBTemp);
|
||||
EEPROM_WRITE_VAR(i,absPreheatFanSpeed);
|
||||
*/
|
||||
|
||||
EEPROM_WRITE_VAR(i,zprobe_zoffset);
|
||||
#ifdef PIDTEMP
|
||||
|
@ -89,6 +95,11 @@ void Config_StoreSettings()
|
|||
EEPROM_WRITE_VAR(i,dummy);
|
||||
EEPROM_WRITE_VAR(i,dummy);
|
||||
#endif
|
||||
#ifdef PIDTEMPBED
|
||||
EEPROM_WRITE_VAR(i, bedKp);
|
||||
EEPROM_WRITE_VAR(i, bedKi);
|
||||
EEPROM_WRITE_VAR(i, bedKd);
|
||||
#endif
|
||||
#ifndef DOGLCD
|
||||
int lcd_contrast = 32;
|
||||
#endif
|
||||
|
@ -117,9 +128,17 @@ void Config_StoreSettings()
|
|||
EEPROM_WRITE_VAR(i, filament_size[2]);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
if (level >= 10) {
|
||||
EEPROM_WRITE_VAR(i, extruder_advance_k);
|
||||
EEPROM_WRITE_VAR(i, advance_ed_ratio);
|
||||
}
|
||||
/*MYSERIAL.print("Top address used:\n");
|
||||
MYSERIAL.print(i);
|
||||
MYSERIAL.print("\n");
|
||||
*/
|
||||
char ver2[4]=EEPROM_VERSION;
|
||||
i=EEPROM_OFFSET;
|
||||
i=offset;
|
||||
EEPROM_WRITE_VAR(i,ver2); // validate data
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNPGM("Settings Stored");
|
||||
|
@ -128,9 +147,10 @@ void Config_StoreSettings()
|
|||
|
||||
|
||||
#ifndef DISABLE_M503
|
||||
void Config_PrintSettings()
|
||||
void Config_PrintSettings(uint8_t level)
|
||||
{ // Always have this function, even with EEPROM_SETTINGS disabled, the current values will be shown
|
||||
SERIAL_ECHO_START;
|
||||
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNPGM("Steps per unit:");
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOPAIR(" M92 X",axis_steps_per_unit[X_AXIS]);
|
||||
|
@ -169,9 +189,10 @@ void Config_PrintSettings()
|
|||
SERIAL_ECHOPAIR(" M205 S",minimumfeedrate );
|
||||
SERIAL_ECHOPAIR(" T" ,mintravelfeedrate );
|
||||
SERIAL_ECHOPAIR(" B" ,minsegmenttime );
|
||||
SERIAL_ECHOPAIR(" X" ,max_xy_jerk );
|
||||
SERIAL_ECHOPAIR(" Z" ,max_z_jerk);
|
||||
SERIAL_ECHOPAIR(" E" ,max_e_jerk);
|
||||
SERIAL_ECHOPAIR(" X" ,max_jerk[X_AXIS] );
|
||||
SERIAL_ECHOPAIR(" Y" ,max_jerk[Y_AXIS] );
|
||||
SERIAL_ECHOPAIR(" Z" ,max_jerk[Z_AXIS] );
|
||||
SERIAL_ECHOPAIR(" E" ,max_jerk[E_AXIS] );
|
||||
SERIAL_ECHOLN("");
|
||||
|
||||
SERIAL_ECHO_START;
|
||||
|
@ -190,6 +211,15 @@ void Config_PrintSettings()
|
|||
SERIAL_ECHOPAIR(" D" ,unscalePID_d(Kd));
|
||||
SERIAL_ECHOLN("");
|
||||
#endif
|
||||
#ifdef PIDTEMPBED
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNPGM("PID heatbed settings:");
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOPAIR(" M304 P", bedKp);
|
||||
SERIAL_ECHOPAIR(" I", unscalePID_i(bedKi));
|
||||
SERIAL_ECHOPAIR(" D", unscalePID_d(bedKd));
|
||||
SERIAL_ECHOLN("");
|
||||
#endif
|
||||
#ifdef FWRETRACT
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNPGM("Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)");
|
||||
|
@ -239,14 +269,22 @@ void Config_PrintSettings()
|
|||
SERIAL_ECHOLNPGM("Filament settings: Disabled");
|
||||
}
|
||||
#endif
|
||||
if (level >= 10) {
|
||||
#ifdef LIN_ADVANCE
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNPGM("Linear advance settings:");
|
||||
SERIAL_ECHOPAIR(" M900 K", extruder_advance_k);
|
||||
SERIAL_ECHOPAIR(" E/D = ", advance_ed_ratio);
|
||||
#endif //LIN_ADVANCE
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef EEPROM_SETTINGS
|
||||
void Config_RetrieveSettings()
|
||||
void Config_RetrieveSettings(uint16_t offset, uint8_t level)
|
||||
{
|
||||
int i=EEPROM_OFFSET;
|
||||
int i=offset;
|
||||
char stored_ver[4];
|
||||
char ver[4]=EEPROM_VERSION;
|
||||
EEPROM_READ_VAR(i,stored_ver); //read stored version
|
||||
|
@ -266,22 +304,24 @@ void Config_RetrieveSettings()
|
|||
EEPROM_READ_VAR(i,minimumfeedrate);
|
||||
EEPROM_READ_VAR(i,mintravelfeedrate);
|
||||
EEPROM_READ_VAR(i,minsegmenttime);
|
||||
EEPROM_READ_VAR(i,max_xy_jerk);
|
||||
EEPROM_READ_VAR(i,max_z_jerk);
|
||||
EEPROM_READ_VAR(i,max_e_jerk);
|
||||
EEPROM_READ_VAR(i,max_jerk[X_AXIS]);
|
||||
EEPROM_READ_VAR(i,max_jerk[Y_AXIS]);
|
||||
EEPROM_READ_VAR(i,max_jerk[Z_AXIS]);
|
||||
EEPROM_READ_VAR(i,max_jerk[E_AXIS]);
|
||||
EEPROM_READ_VAR(i,add_homing);
|
||||
#ifndef ULTIPANEL
|
||||
int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed;
|
||||
int absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed;
|
||||
|
||||
#endif
|
||||
/*
|
||||
EEPROM_READ_VAR(i,plaPreheatHotendTemp);
|
||||
EEPROM_READ_VAR(i,plaPreheatHPBTemp);
|
||||
EEPROM_READ_VAR(i,plaPreheatFanSpeed);
|
||||
EEPROM_READ_VAR(i,absPreheatHotendTemp);
|
||||
EEPROM_READ_VAR(i,absPreheatHPBTemp);
|
||||
EEPROM_READ_VAR(i,absPreheatFanSpeed);
|
||||
|
||||
*/
|
||||
|
||||
|
||||
EEPROM_READ_VAR(i,zprobe_zoffset);
|
||||
|
@ -292,7 +332,12 @@ void Config_RetrieveSettings()
|
|||
EEPROM_READ_VAR(i,Kp);
|
||||
EEPROM_READ_VAR(i,Ki);
|
||||
EEPROM_READ_VAR(i,Kd);
|
||||
#ifndef DOGLCD
|
||||
#ifdef PIDTEMPBED
|
||||
EEPROM_READ_VAR(i, bedKp);
|
||||
EEPROM_READ_VAR(i, bedKi);
|
||||
EEPROM_READ_VAR(i, bedKd);
|
||||
#endif
|
||||
#ifndef DOGLCD
|
||||
int lcd_contrast;
|
||||
#endif
|
||||
EEPROM_READ_VAR(i,lcd_contrast);
|
||||
|
@ -320,6 +365,10 @@ void Config_RetrieveSettings()
|
|||
EEPROM_READ_VAR(i, filament_size[2]);
|
||||
#endif
|
||||
#endif
|
||||
if (level >= 10) {
|
||||
EEPROM_READ_VAR(i, extruder_advance_k);
|
||||
EEPROM_READ_VAR(i, advance_ed_ratio);
|
||||
}
|
||||
calculate_volumetric_multipliers();
|
||||
// Call updatePID (similar to when we have processed M301)
|
||||
updatePID();
|
||||
|
@ -356,20 +405,12 @@ void Config_ResetDefault()
|
|||
minimumfeedrate=DEFAULT_MINIMUMFEEDRATE;
|
||||
minsegmenttime=DEFAULT_MINSEGMENTTIME;
|
||||
mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
|
||||
max_xy_jerk=DEFAULT_XYJERK;
|
||||
max_z_jerk=DEFAULT_ZJERK;
|
||||
max_e_jerk=DEFAULT_EJERK;
|
||||
max_jerk[X_AXIS] = DEFAULT_XJERK;
|
||||
max_jerk[Y_AXIS] = DEFAULT_YJERK;
|
||||
max_jerk[Z_AXIS] = DEFAULT_ZJERK;
|
||||
max_jerk[E_AXIS] = DEFAULT_EJERK;
|
||||
add_homing[X_AXIS] = add_homing[Y_AXIS] = add_homing[Z_AXIS] = 0;
|
||||
#ifdef ULTIPANEL
|
||||
plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP;
|
||||
plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP;
|
||||
plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED;
|
||||
absPreheatHotendTemp = ABS_PREHEAT_HOTEND_TEMP;
|
||||
absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP;
|
||||
absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED;
|
||||
|
||||
|
||||
#endif
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
zprobe_zoffset = -Z_PROBE_OFFSET_FROM_EXTRUDER;
|
||||
#endif
|
||||
|
|
|
@ -1,22 +1,27 @@
|
|||
#ifndef CONFIG_STORE_H
|
||||
#define CONFIG_STORE_H
|
||||
#define EEPROM_SETTINGS
|
||||
|
||||
#include "Configuration.h"
|
||||
|
||||
void Config_ResetDefault();
|
||||
|
||||
#ifndef DISABLE_M503
|
||||
void Config_PrintSettings();
|
||||
void Config_PrintSettings(uint8_t level = 0);
|
||||
#else
|
||||
FORCE_INLINE void Config_PrintSettings() {}
|
||||
#endif
|
||||
|
||||
#ifdef EEPROM_SETTINGS
|
||||
void Config_StoreSettings();
|
||||
void Config_RetrieveSettings();
|
||||
void Config_StoreSettings(uint16_t offset, uint8_t level = 0);
|
||||
void Config_RetrieveSettings(uint16_t offset, uint8_t level = 0);
|
||||
#else
|
||||
FORCE_INLINE void Config_StoreSettings() {}
|
||||
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
|
||||
#endif
|
||||
|
||||
inline uint8_t calibration_status() { return eeprom_read_byte((uint8_t*)EEPROM_CALIBRATION_STATUS); }
|
||||
inline uint8_t calibration_status_store(uint8_t status) { eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS, status); }
|
||||
inline bool calibration_status_pinda() { return eeprom_read_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA); }
|
||||
|
||||
#endif//CONFIG_STORE_H
|
||||
|
|
|
@ -68,7 +68,7 @@
|
|||
// When first starting the main fan, run it at full speed for the
|
||||
// given number of milliseconds. This gets the fan spinning reliably
|
||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
//#define FAN_KICKSTART_TIME 100
|
||||
#define FAN_KICKSTART_TIME 800
|
||||
|
||||
|
||||
|
||||
|
@ -265,24 +265,45 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
// extruder advance constant (s2/mm3)
|
||||
//
|
||||
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
|
||||
//
|
||||
// Hooke's law says: force = k * distance
|
||||
// Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant
|
||||
// so: v ^ 2 is proportional to number of steps we advance the extruder
|
||||
//#define ADVANCE
|
||||
/**
|
||||
* Implementation of linear pressure control
|
||||
*
|
||||
* Assumption: advance = k * (delta velocity)
|
||||
* K=0 means advance disabled.
|
||||
* See Marlin documentation for calibration instructions.
|
||||
*/
|
||||
#define LIN_ADVANCE
|
||||
|
||||
#ifdef ADVANCE
|
||||
#define EXTRUDER_ADVANCE_K .006
|
||||
#ifdef LIN_ADVANCE
|
||||
#define LIN_ADVANCE_K 0 //Try around 45 for PLA, around 25 for ABS.
|
||||
|
||||
#define D_FILAMENT 1.75
|
||||
#define STEPS_MM_E 174.6
|
||||
#define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
|
||||
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUSION_AREA)
|
||||
|
||||
#endif // ADVANCE
|
||||
/**
|
||||
* 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
|
||||
#endif
|
||||
|
||||
// Arc interpretation settings:
|
||||
#define MM_PER_ARC_SEGMENT 1
|
||||
|
@ -335,6 +356,10 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
|||
//The ASCII buffer for receiving from the serial:
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define BUFSIZE 4
|
||||
// The command header contains the following values:
|
||||
// 1st byte: the command source (CMDBUFFER_CURRENT_TYPE_USB, CMDBUFFER_CURRENT_TYPE_SDCARD, CMDBUFFER_CURRENT_TYPE_UI or CMDBUFFER_CURRENT_TYPE_CHAINED)
|
||||
// 2nd and 3rd byte (LSB first) contains a 16bit length of a command including its preceding comments.
|
||||
#define CMDHDRSIZE 3
|
||||
|
||||
|
||||
// Firmware based and LCD controlled retract
|
||||
|
@ -392,6 +417,12 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
|||
#define THERMISTORBED TEMP_SENSOR_BED
|
||||
#define BED_USES_THERMISTOR
|
||||
#endif
|
||||
#if TEMP_SENSOR_PINDA > 0
|
||||
#define THERMISTORPINDA TEMP_SENSOR_PINDA
|
||||
#endif
|
||||
#if TEMP_SENSOR_AMBIENT > 0
|
||||
#define THERMISTORAMBIENT TEMP_SENSOR_AMBIENT
|
||||
#endif
|
||||
#if TEMP_SENSOR_0 == -1
|
||||
#define HEATER_0_USES_AD595
|
||||
#endif
|
||||
|
|
530
Firmware/Configuration_prusa.h
Normal file
530
Firmware/Configuration_prusa.h
Normal file
|
@ -0,0 +1,530 @@
|
|||
#ifndef CONFIGURATION_PRUSA_H
|
||||
#define CONFIGURATION_PRUSA_H
|
||||
|
||||
/*------------------------------------
|
||||
GENERAL SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Printer revision
|
||||
#define FILAMENT_SIZE "1_75mm_MK3"
|
||||
#define NOZZLE_TYPE "E3Dv6full"
|
||||
|
||||
// Developer flag
|
||||
#define DEVELOPER
|
||||
|
||||
// Printer name
|
||||
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
||||
|
||||
// Electronics
|
||||
#define MOTHERBOARD BOARD_EINSY_0_4a
|
||||
|
||||
|
||||
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
||||
//#define E3D_PT100_EXTRUDER_WITH_AMP
|
||||
//#define E3D_PT100_EXTRUDER_NO_AMP
|
||||
//#define E3D_PT100_BED_WITH_AMP
|
||||
//#define E3D_PT100_BED_NO_AMP
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
AXIS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Steps per unit {X,Y,Z,E}
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,560}
|
||||
|
||||
// Endstop inverting
|
||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
|
||||
// Home position
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS -2.2
|
||||
#define MANUAL_Z_HOME_POS 0.2
|
||||
|
||||
// Travel limits after homing
|
||||
#define X_MAX_POS 255
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MAX_POS 210
|
||||
#define Y_MIN_POS -4 //orig -4
|
||||
#define Z_MAX_POS 210
|
||||
#define Z_MIN_POS 0.15
|
||||
|
||||
// Canceled home position
|
||||
#define X_CANCEL_POS 50
|
||||
#define Y_CANCEL_POS 190
|
||||
|
||||
//Pause print position
|
||||
#define X_PAUSE_POS 50
|
||||
#define Y_PAUSE_POS 190
|
||||
#define Z_PAUSE_LIFT 20
|
||||
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {2500, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
|
||||
|
||||
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
|
||||
|
||||
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||
|
||||
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||
|
||||
#define Z_AXIS_ALWAYS_ON 1
|
||||
|
||||
// Automatic recovery after crash is detected
|
||||
#define AUTOMATIC_RECOVERY_AFTER_CRASH
|
||||
|
||||
//DEBUG
|
||||
//#define _NO_ASM
|
||||
#define DEBUG_DCODES //D codes
|
||||
#if 1
|
||||
//#define DEBUG_FSENSOR_LOG //Reports fsensor status to serial
|
||||
//#define DEBUG_CRASHDET_COUNTERS //Display crash-detection counters on LCD
|
||||
//#define DEBUG_RESUME_PRINT //Resume/save print debug enable
|
||||
//#define DEBUG_UVLO_AUTOMATIC_RECOVER // Power panic automatic recovery debug output
|
||||
//#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||
//#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||
//#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||
//#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||
//#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||
//#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||
//#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||
//#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||
//#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||
//#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||
//#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||
//#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_BLINK_ACTIVE
|
||||
#endif
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
TMC2130 default settings
|
||||
*------------------------------------*/
|
||||
|
||||
#define TMC2130_FCLK 12000000 // fclk = 12MHz
|
||||
|
||||
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||
#define TMC2130_USTEPS_E 64 // microstep resolution for E axis
|
||||
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||
|
||||
#define TMC2130_PWM_GRAD_X 2 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_X 230 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||
|
||||
#define TMC2130_PWM_GRAD_Y 2 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Y 235 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||
|
||||
/* //not used
|
||||
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
|
||||
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||
*/
|
||||
|
||||
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||
|
||||
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||
#define TMC2130_THIGH 0 // THIGH - unused
|
||||
|
||||
//#define TMC2130_TCOOLTHRS_X 450 // TCOOLTHRS - coolstep treshold
|
||||
//#define TMC2130_TCOOLTHRS_Y 450 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_X 430 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_Y 430 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_Z 500 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_E 500 // TCOOLTHRS - coolstep treshold
|
||||
|
||||
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||
#define TMC2130_SG_THRS_X 3 // stallguard sensitivity for X axis
|
||||
#define TMC2130_SG_THRS_Y 4 // stallguard sensitivity for Y axis
|
||||
#define TMC2130_SG_THRS_Z 3 // stallguard sensitivity for Z axis
|
||||
#define TMC2130_SG_THRS_E 3 // stallguard sensitivity for E axis
|
||||
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||
|
||||
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||
#define TMC2130_CURRENTS_H {13, 20, 20, 35} // default holding currents for all axes
|
||||
#define TMC2130_CURRENTS_R {13, 20, 20, 35} // default running currents for all axes
|
||||
|
||||
//#define TMC2130_DEBUG
|
||||
//#define TMC2130_DEBUG_WR
|
||||
//#define TMC2130_DEBUG_RD
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
EXTRUDER SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Mintemps
|
||||
#define HEATER_0_MINTEMP 15
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define BED_MINTEMP 15
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define HEATER_0_MAXTEMP 410
|
||||
#else
|
||||
#define HEATER_0_MAXTEMP 305
|
||||
#endif
|
||||
#define HEATER_1_MAXTEMP 305
|
||||
#define HEATER_2_MAXTEMP 305
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_Kp 21.70
|
||||
#define DEFAULT_Ki 1.60
|
||||
#define DEFAULT_Kd 73.76
|
||||
#else
|
||||
// Define PID constants for extruder
|
||||
//#define DEFAULT_Kp 40.925
|
||||
//#define DEFAULT_Ki 4.875
|
||||
//#define DEFAULT_Kd 86.085
|
||||
#define DEFAULT_Kp 16.13
|
||||
#define DEFAULT_Ki 1.1625
|
||||
#define DEFAULT_Kd 56.23
|
||||
#endif
|
||||
|
||||
// Extrude mintemp
|
||||
#define EXTRUDE_MINTEMP 130
|
||||
|
||||
// Extruder cooling fans
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN 8
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
LOAD/UNLOAD FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Load filament commands
|
||||
#define LOAD_FILAMENT_0 "M83"
|
||||
#define LOAD_FILAMENT_1 "G1 E70 F400"
|
||||
#define LOAD_FILAMENT_2 "G1 E40 F100"
|
||||
|
||||
// Unload filament commands
|
||||
#define UNLOAD_FILAMENT_0 "M83"
|
||||
#define UNLOAD_FILAMENT_1 "G1 E-80 F7000"
|
||||
|
||||
/*------------------------------------
|
||||
CHANGE FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Filament change configuration
|
||||
#define FILAMENTCHANGEENABLE
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#define FILAMENTCHANGE_XPOS 211
|
||||
#define FILAMENTCHANGE_YPOS 0
|
||||
#define FILAMENTCHANGE_ZADD 2
|
||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||
#define FILAMENTCHANGE_FINALRETRACT -80
|
||||
|
||||
#define FILAMENTCHANGE_FIRSTFEED 70
|
||||
#define FILAMENTCHANGE_FINALFEED 50
|
||||
#define FILAMENTCHANGE_RECFEED 5
|
||||
|
||||
#define FILAMENTCHANGE_XYFEED 50
|
||||
#define FILAMENTCHANGE_EFEED 20
|
||||
//#define FILAMENTCHANGE_RFEED 400
|
||||
#define FILAMENTCHANGE_RFEED 7000 / 60
|
||||
#define FILAMENTCHANGE_EXFEED 2
|
||||
#define FILAMENTCHANGE_ZFEED 15
|
||||
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
ADDITIONAL FEATURES SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Prusa filament runout sensor
|
||||
//#define FILAMENT_RUNOUT_SUPPORT
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SUPPORT
|
||||
#define FILAMENT_RUNOUT_SENSOR 1
|
||||
#endif
|
||||
|
||||
// temperature runaway
|
||||
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||
|
||||
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||
|
||||
/*------------------------------------
|
||||
MOTOR CURRENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Motor Current setting for BIG RAMBo
|
||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||
|
||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
PAT9125 SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
#define PAT9125_XRES 200
|
||||
#define PAT9125_YRES 200
|
||||
|
||||
/*------------------------------------
|
||||
BED SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Mesh Bed Leveling system to enable it
|
||||
#define MESH_BED_LEVELING
|
||||
#ifdef MESH_BED_LEVELING
|
||||
|
||||
#define MBL_Z_STEP 0.01
|
||||
|
||||
// Mesh definitions
|
||||
#define MESH_MIN_X 35
|
||||
#define MESH_MAX_X 238
|
||||
#define MESH_MIN_Y 6
|
||||
#define MESH_MAX_Y 202
|
||||
|
||||
// Mesh upsample definition
|
||||
#define MESH_NUM_X_POINTS 7
|
||||
#define MESH_NUM_Y_POINTS 7
|
||||
// Mesh measure definition
|
||||
#define MESH_MEAS_NUM_X_POINTS 3
|
||||
#define MESH_MEAS_NUM_Y_POINTS 3
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
||||
#endif
|
||||
|
||||
// Bed Temperature Control
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
// Bed temperature compensation settings
|
||||
#define BED_OFFSET 10
|
||||
#define BED_OFFSET_START 40
|
||||
#define BED_OFFSET_CENTER 50
|
||||
|
||||
|
||||
#ifdef PIDTEMPBED
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_bedKp 21.70
|
||||
#define DEFAULT_bedKi 1.60
|
||||
#define DEFAULT_bedKd 73.76
|
||||
#else
|
||||
#define DEFAULT_bedKp 126.13
|
||||
#define DEFAULT_bedKi 4.30
|
||||
#define DEFAULT_bedKd 924.76
|
||||
#endif
|
||||
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from pidautotune
|
||||
// #define DEFAULT_bedKp 97.1
|
||||
// #define DEFAULT_bedKi 1.41
|
||||
// #define DEFAULT_bedKd 1675.16
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#endif // PIDTEMPBED
|
||||
|
||||
|
||||
/*-----------------------------------
|
||||
PREHEAT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 40
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 240
|
||||
#define PET_PREHEAT_HPB_TEMP 90
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
|
||||
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 1010 is Pt1000 with 1k pullup (non standard)
|
||||
// 147 is Pt100 with 4k7 pullup
|
||||
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
|
||||
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
|
||||
// 110 is Pt100 with 1k pullup (non standard)
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
|
||||
#define TEMP_SENSOR_0 247
|
||||
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define TEMP_SENSOR_0 148
|
||||
#else
|
||||
#define TEMP_SENSOR_0 5
|
||||
#endif
|
||||
#define TEMP_SENSOR_1 0
|
||||
#define TEMP_SENSOR_2 0
|
||||
#if defined(E3D_PT100_BED_WITH_AMP)
|
||||
#define TEMP_SENSOR_BED 247
|
||||
#elif defined(E3D_PT100_BED_NO_AMP)
|
||||
#define TEMP_SENSOR_BED 148
|
||||
#else
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#endif
|
||||
#define TEMP_SENSOR_PINDA 1
|
||||
#define TEMP_SENSOR_AMBIENT 2000
|
||||
|
||||
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||
|
||||
#define MAX_BED_TEMP_CALIBRATION 50
|
||||
#define MAX_HOTEND_TEMP_CALIBRATION 50
|
||||
|
||||
#define MAX_E_STEPS_PER_UNIT 250
|
||||
#define MIN_E_STEPS_PER_UNIT 100
|
||||
|
||||
#define Z_BABYSTEP_MIN -3999
|
||||
#define Z_BABYSTEP_MAX 0
|
||||
|
||||
#define PINDA_PREHEAT_X 20
|
||||
#define PINDA_PREHEAT_Y 60
|
||||
#define PINDA_PREHEAT_Z 0.15
|
||||
/*
|
||||
#define PINDA_PREHEAT_X 70
|
||||
#define PINDA_PREHEAT_Y -3
|
||||
#define PINDA_PREHEAT_Z 1*/
|
||||
#define PINDA_HEAT_T 120 //time in s
|
||||
|
||||
#define PINDA_MIN_T 50
|
||||
#define PINDA_STEP_T 10
|
||||
#define PINDA_MAX_T 100
|
||||
|
||||
#define PING_TIME 60 //time in s
|
||||
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
|
||||
#define PING_ALLERT_PERIOD 60 //time in s
|
||||
|
||||
#define LONG_PRESS_TIME 1000 //time in ms for button long press
|
||||
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
|
||||
|
||||
#define DEFAULT_PID_TEMP 210
|
||||
|
||||
#define MIN_PRINT_FAN_SPEED 75
|
||||
|
||||
#ifdef SNMM
|
||||
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
|
||||
#else
|
||||
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||
#endif
|
||||
|
||||
// How much shall the print head be lifted on power panic?
|
||||
// Ideally the Z axis will reach a zero phase of the stepper driver on power outage. To simplify this,
|
||||
// UVLO_Z_AXIS_SHIFT shall be an integer multiply of the stepper driver cycle, that is 4x full step.
|
||||
// For example, the Prusa i3 MK2 with 16 microsteps per full step has Z stepping of 400 microsteps per mm.
|
||||
// At 400 microsteps per mm, a full step lifts the Z axis by 0.04mm, and a stepper driver cycle is 0.16mm.
|
||||
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
|
||||
//#define UVLO_Z_AXIS_SHIFT 1.92
|
||||
#define 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.
|
||||
#define AUTOMATIC_UVLO_BED_TEMP_OFFSET 5
|
||||
|
||||
#define HEATBED_V2
|
||||
|
||||
//#define SUPPORT_VERBOSITY
|
||||
|
||||
#endif //__CONFIGURATION_PRUSA_H
|
462
Firmware/Dcodes.cpp
Normal file
462
Firmware/Dcodes.cpp
Normal file
|
@ -0,0 +1,462 @@
|
|||
#include "Dcodes.h"
|
||||
#include "Marlin.h"
|
||||
|
||||
#ifdef DEBUG_DCODES
|
||||
|
||||
#include "ConfigurationStore.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "pat9125.h"
|
||||
#include <avr/wdt.h>
|
||||
|
||||
|
||||
#define FLASHSIZE 0x40000
|
||||
|
||||
#define RAMSIZE 0x2000
|
||||
#define boot_src_addr (*((uint32_t*)(RAMSIZE - 16)))
|
||||
#define boot_dst_addr (*((uint32_t*)(RAMSIZE - 12)))
|
||||
#define boot_copy_size (*((uint16_t*)(RAMSIZE - 8)))
|
||||
#define boot_reserved (*((uint8_t*)(RAMSIZE - 6)))
|
||||
#define boot_app_flags (*((uint8_t*)(RAMSIZE - 5)))
|
||||
#define boot_app_magic (*((uint32_t*)(RAMSIZE - 4)))
|
||||
#define BOOT_APP_FLG_ERASE 0x01
|
||||
#define BOOT_APP_FLG_COPY 0x02
|
||||
#define BOOT_APP_FLG_FLASH 0x04
|
||||
|
||||
extern uint8_t fsensor_log;
|
||||
extern float current_temperature_pinda;
|
||||
extern float axis_steps_per_unit[NUM_AXIS];
|
||||
|
||||
|
||||
inline void print_hex_nibble(uint8_t val)
|
||||
{
|
||||
putchar((val > 9)?(val - 10 + 'a'):(val + '0'));
|
||||
}
|
||||
|
||||
void print_hex_byte(uint8_t val)
|
||||
{
|
||||
print_hex_nibble(val >> 4);
|
||||
print_hex_nibble(val & 15);
|
||||
}
|
||||
|
||||
void print_hex_word(uint16_t val)
|
||||
{
|
||||
print_hex_byte(val >> 8);
|
||||
print_hex_byte(val & 255);
|
||||
}
|
||||
|
||||
void print_mem(uint32_t address, uint16_t count, uint8_t type, uint8_t countperline = 16)
|
||||
{
|
||||
while (count)
|
||||
{
|
||||
if (type == 2)
|
||||
print_hex_nibble(address >> 16);
|
||||
print_hex_word(address);
|
||||
putchar(' ');
|
||||
uint8_t count_line = countperline;
|
||||
while (count && count_line)
|
||||
{
|
||||
uint8_t data = 0;
|
||||
switch (type)
|
||||
{
|
||||
case 0: data = *((uint8_t*)address++); break;
|
||||
case 1: data = eeprom_read_byte((uint8_t*)address++); break;
|
||||
case 2: data = pgm_read_byte_far((uint8_t*)address++); break;
|
||||
}
|
||||
putchar(' ');
|
||||
print_hex_byte(data);
|
||||
count_line--;
|
||||
count--;
|
||||
}
|
||||
putchar('\n');
|
||||
}
|
||||
}
|
||||
|
||||
//#define LOG(args...) printf(args)
|
||||
#define LOG(args...)
|
||||
|
||||
int parse_hex(char* hex, uint8_t* data, int count)
|
||||
{
|
||||
int parsed = 0;
|
||||
while (*hex)
|
||||
{
|
||||
if (count && (parsed >= count)) break;
|
||||
char c = *(hex++);
|
||||
if (c == ' ') continue;
|
||||
if (c == '\n') break;
|
||||
uint8_t val = 0x00;
|
||||
if ((c >= '0') && (c <= '9')) val |= ((c - '0') << 4);
|
||||
else if ((c >= 'a') && (c <= 'f')) val |= ((c - 'a' + 10) << 4);
|
||||
else return -parsed;
|
||||
c = *(hex++);
|
||||
if ((c >= '0') && (c <= '9')) val |= (c - '0');
|
||||
else if ((c >= 'a') && (c <= 'f')) val |= (c - 'a' + 10);
|
||||
else return -parsed;
|
||||
data[parsed] = val;
|
||||
parsed++;
|
||||
}
|
||||
return parsed;
|
||||
}
|
||||
|
||||
void dcode__1()
|
||||
{
|
||||
printf("D-1 - Endless loop\n");
|
||||
cli();
|
||||
while (1);
|
||||
}
|
||||
|
||||
void dcode_0()
|
||||
{
|
||||
if (*(strchr_pointer + 1) == 0) return;
|
||||
LOG("D0 - Reset\n");
|
||||
if (code_seen('B')) //bootloader
|
||||
{
|
||||
cli();
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
}
|
||||
else //reset
|
||||
{
|
||||
#ifndef _NO_ASM
|
||||
asm volatile("jmp 0x00000");
|
||||
#endif //_NO_ASM
|
||||
}
|
||||
}
|
||||
|
||||
void dcode_1()
|
||||
{
|
||||
LOG("D1 - Clear EEPROM and RESET\n");
|
||||
cli();
|
||||
for (int i = 0; i < 8192; i++)
|
||||
eeprom_write_byte((unsigned char*)i, (unsigned char)0xff);
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
}
|
||||
|
||||
void dcode_2()
|
||||
{
|
||||
LOG("D2 - Read/Write RAM\n");
|
||||
uint16_t address = 0x0000; //default 0x0000
|
||||
uint16_t count = 0x2000; //default 0x2000 (entire ram)
|
||||
if (code_seen('A')) // Address (0x0000-0x1fff)
|
||||
address = (strchr_pointer[1] == 'x')?strtol(strchr_pointer + 2, 0, 16):(int)code_value();
|
||||
if (code_seen('C')) // Count (0x0001-0x2000)
|
||||
count = (int)code_value();
|
||||
address &= 0x1fff;
|
||||
if (count > 0x2000) count = 0x2000;
|
||||
if ((address + count) > 0x2000) count = 0x2000 - address;
|
||||
if (code_seen('X')) // Data
|
||||
{
|
||||
uint8_t data[16];
|
||||
count = parse_hex(strchr_pointer + 1, data, 16);
|
||||
if (count > 0)
|
||||
{
|
||||
for (int i = 0; i < count; i++)
|
||||
*((uint8_t*)(address + i)) = data[i];
|
||||
LOG("%d bytes written to RAM at address %04x", count, address);
|
||||
}
|
||||
else
|
||||
count = 0;
|
||||
}
|
||||
print_mem(address, count, 0);
|
||||
/* while (count)
|
||||
{
|
||||
print_hex_word(address);
|
||||
putchar(' ');
|
||||
uint8_t countperline = 16;
|
||||
while (count && countperline)
|
||||
{
|
||||
uint8_t data = *((uint8_t*)address++);
|
||||
putchar(' ');
|
||||
print_hex_byte(data);
|
||||
countperline--;
|
||||
count--;
|
||||
}
|
||||
putchar('\n');
|
||||
}*/
|
||||
}
|
||||
|
||||
void dcode_3()
|
||||
{
|
||||
LOG("D3 - Read/Write EEPROM\n");
|
||||
uint16_t address = 0x0000; //default 0x0000
|
||||
uint16_t count = 0x2000; //default 0x2000 (entire eeprom)
|
||||
if (code_seen('A')) // Address (0x0000-0x1fff)
|
||||
address = (strchr_pointer[1] == 'x')?strtol(strchr_pointer + 2, 0, 16):(int)code_value();
|
||||
if (code_seen('C')) // Count (0x0001-0x2000)
|
||||
count = (int)code_value();
|
||||
address &= 0x1fff;
|
||||
if (count > 0x2000) count = 0x2000;
|
||||
if ((address + count) > 0x2000) count = 0x2000 - address;
|
||||
if (code_seen('X')) // Data
|
||||
{
|
||||
uint8_t data[16];
|
||||
count = parse_hex(strchr_pointer + 1, data, 16);
|
||||
if (count > 0)
|
||||
{
|
||||
for (int i = 0; i < count; i++)
|
||||
eeprom_write_byte((uint8_t*)(address + i), data[i]);
|
||||
LOG(count, DEC);
|
||||
LOG(" bytes written to EEPROM at address ");
|
||||
print_hex_word(address);
|
||||
putchar('\n');
|
||||
}
|
||||
else
|
||||
count = 0;
|
||||
}
|
||||
print_mem(address, count, 1);
|
||||
/* while (count)
|
||||
{
|
||||
print_hex_word(address);
|
||||
putchar(' ');
|
||||
uint8_t countperline = 16;
|
||||
while (count && countperline)
|
||||
{
|
||||
uint8_t data = eeprom_read_byte((uint8_t*)address++);
|
||||
putchar(' ');
|
||||
print_hex_byte(data);
|
||||
countperline--;
|
||||
count--;
|
||||
}
|
||||
putchar('\n');
|
||||
}*/
|
||||
}
|
||||
|
||||
void dcode_4()
|
||||
{
|
||||
LOG("D4 - Read/Write PIN\n");
|
||||
if (code_seen('P')) // Pin (0-255)
|
||||
{
|
||||
int pin = (int)code_value();
|
||||
if ((pin >= 0) && (pin <= 255))
|
||||
{
|
||||
if (code_seen('F')) // Function in/out (0/1)
|
||||
{
|
||||
int fnc = (int)code_value();
|
||||
if (fnc == 0) pinMode(pin, INPUT);
|
||||
else if (fnc == 1) pinMode(pin, OUTPUT);
|
||||
}
|
||||
if (code_seen('V')) // Value (0/1)
|
||||
{
|
||||
int val = (int)code_value();
|
||||
if (val == 0) digitalWrite(pin, LOW);
|
||||
else if (val == 1) digitalWrite(pin, HIGH);
|
||||
}
|
||||
else
|
||||
{
|
||||
int val = (digitalRead(pin) != LOW)?1:0;
|
||||
printf("PIN%d=%d", pin, val);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
/*
|
||||
void dcode_5()
|
||||
{
|
||||
LOG("D5 - Read/Write FLASH\n");
|
||||
uint32_t address = 0x0000; //default 0x0000
|
||||
uint16_t count = 0x0400; //default 0x0400 (1kb block)
|
||||
if (code_seen('A')) // Address (0x00000-0x3ffff)
|
||||
address = (strchr_pointer[1] == 'x')?strtol(strchr_pointer + 2, 0, 16):(int)code_value();
|
||||
if (code_seen('C')) // Count (0x0001-0x2000)
|
||||
count = (int)code_value();
|
||||
address &= 0x3ffff;
|
||||
if (count > 0x2000) count = 0x2000;
|
||||
if ((address + count) > 0x40000) count = 0x40000 - address;
|
||||
bool bErase = false;
|
||||
bool bCopy = false;
|
||||
if (code_seen('E')) //Erase
|
||||
bErase = true;
|
||||
uint8_t data[16];
|
||||
if (code_seen('X')) // Data
|
||||
{
|
||||
count = parse_hex(strchr_pointer + 1, data, 16);
|
||||
if (count > 0) bCopy = true;
|
||||
}
|
||||
if (bErase || bCopy)
|
||||
{
|
||||
if (bErase)
|
||||
{
|
||||
LOG(count, DEC);
|
||||
LOG(" bytes of FLASH at address ");
|
||||
print_hex_word(address);
|
||||
putchar(" will be erased\n");
|
||||
}
|
||||
if (bCopy)
|
||||
{
|
||||
LOG(count, DEC);
|
||||
LOG(" bytes will be written to FLASH at address ");
|
||||
print_hex_word(address);
|
||||
putchar('\n');
|
||||
}
|
||||
cli();
|
||||
boot_app_magic = 0x55aa55aa;
|
||||
boot_app_flags = (bErase?(BOOT_APP_FLG_ERASE):0) | (bCopy?(BOOT_APP_FLG_COPY):0);
|
||||
boot_copy_size = (uint16_t)count;
|
||||
boot_dst_addr = (uint32_t)address;
|
||||
boot_src_addr = (uint32_t)(&data);
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
}
|
||||
while (count)
|
||||
{
|
||||
print_hex_nibble(address >> 16);
|
||||
print_hex_word(address);
|
||||
putchar(' ');
|
||||
uint8_t countperline = 16;
|
||||
while (count && countperline)
|
||||
{
|
||||
uint8_t data = pgm_read_byte_far((uint8_t*)address++);
|
||||
putchar(' ');
|
||||
print_hex_byte(data);
|
||||
countperline--;
|
||||
count--;
|
||||
}
|
||||
putchar('\n');
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
void dcode_6()
|
||||
{
|
||||
LOG("D6 - Read/Write external FLASH\n");
|
||||
}
|
||||
|
||||
void dcode_7()
|
||||
{
|
||||
LOG("D7 - Read/Write Bootloader\n");
|
||||
/*
|
||||
cli();
|
||||
boot_app_magic = 0x55aa55aa;
|
||||
boot_app_flags = BOOT_APP_FLG_ERASE | BOOT_APP_FLG_COPY | BOOT_APP_FLG_FLASH;
|
||||
boot_copy_size = (uint16_t)0xc00;
|
||||
boot_src_addr = (uint32_t)0x0003e400;
|
||||
boot_dst_addr = (uint32_t)0x0003f400;
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
*/
|
||||
}
|
||||
|
||||
void dcode_8()
|
||||
{
|
||||
printf_P(PSTR("D8 - Read/Write PINDA\n"));
|
||||
uint8_t cal_status = calibration_status_pinda();
|
||||
float temp_pinda = current_temperature_pinda;
|
||||
float offset_z = temp_compensation_pinda_thermistor_offset(temp_pinda);
|
||||
if ((strchr_pointer[1+1] == '?') || (strchr_pointer[1+1] == 0))
|
||||
{
|
||||
printf_P(PSTR("cal_status=%d\n"), cal_status?1:0);
|
||||
for (uint8_t i = 0; i < 6; i++)
|
||||
{
|
||||
uint16_t offs = 0;
|
||||
if (i > 0) offs = eeprom_read_word(((uint16_t*)EEPROM_PROBE_TEMP_SHIFT) + (i - 1));
|
||||
float foffs = ((float)offs) / axis_steps_per_unit[Z_AXIS];
|
||||
offs = 1000 * foffs;
|
||||
printf_P(PSTR("temp_pinda=%dC temp_shift=%dum\n"), 35 + i * 5, offs);
|
||||
}
|
||||
}
|
||||
else if (strchr_pointer[1+1] == '!')
|
||||
{
|
||||
cal_status = 1;
|
||||
eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, cal_status);
|
||||
eeprom_write_word(((uint16_t*)EEPROM_PROBE_TEMP_SHIFT) + 0, 8); //40C - 20um - 8usteps
|
||||
eeprom_write_word(((uint16_t*)EEPROM_PROBE_TEMP_SHIFT) + 1, 24); //45C - 60um - 24usteps
|
||||
eeprom_write_word(((uint16_t*)EEPROM_PROBE_TEMP_SHIFT) + 2, 48); //50C - 120um - 48usteps
|
||||
eeprom_write_word(((uint16_t*)EEPROM_PROBE_TEMP_SHIFT) + 3, 80); //55C - 200um - 80usteps
|
||||
eeprom_write_word(((uint16_t*)EEPROM_PROBE_TEMP_SHIFT) + 4, 120); //60C - 300um - 120usteps
|
||||
}
|
||||
else
|
||||
{
|
||||
if (code_seen('P')) // Pinda temperature [C]
|
||||
temp_pinda = code_value();
|
||||
offset_z = temp_compensation_pinda_thermistor_offset(temp_pinda);
|
||||
if (code_seen('Z')) // Z Offset [mm]
|
||||
{
|
||||
offset_z = code_value();
|
||||
}
|
||||
}
|
||||
printf_P(PSTR("temp_pinda=%d offset_z=%d.%03d\n"), (int)temp_pinda, (int)offset_z, ((int)(1000 * offset_z) % 1000));
|
||||
}
|
||||
|
||||
void dcode_10()
|
||||
{//Tell the printer that XYZ calibration went OK
|
||||
LOG("D10 - XYZ calibration = OK\n");
|
||||
calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST);
|
||||
}
|
||||
|
||||
void dcode_12()
|
||||
{//Reset Filament error, Power loss and crash counter ( Do it before every print and you can get stats for the print )
|
||||
LOG("D12 - Reset failstat counters\n");
|
||||
eeprom_update_byte((uint8_t*)EEPROM_CRASH_COUNT, 0x00);
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FERROR_COUNT, 0x00);
|
||||
eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, 0x00);
|
||||
}
|
||||
|
||||
#include "tmc2130.h"
|
||||
#include "Marlin.h"
|
||||
#include "planner.h"
|
||||
extern void st_synchronize();
|
||||
|
||||
void dcode_2130()
|
||||
{
|
||||
// printf("test");
|
||||
printf_P(PSTR("D2130 - TMC2130\n"));
|
||||
uint8_t axis = 0xff;
|
||||
if (code_seen('X'))
|
||||
axis = X_AXIS;
|
||||
else if (code_seen('Y'))
|
||||
axis = Y_AXIS;
|
||||
if (axis != 0xff)
|
||||
{
|
||||
homeaxis(axis);
|
||||
tmc2130_sg_meassure_start(axis);
|
||||
memcpy(destination, current_position, sizeof(destination));
|
||||
destination[axis] = 200;
|
||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], homing_feedrate[X_AXIS]/60, active_extruder);
|
||||
st_synchronize();
|
||||
memcpy(destination, current_position, sizeof(destination));
|
||||
destination[axis] = 0;
|
||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], homing_feedrate[X_AXIS]/60, active_extruder);
|
||||
st_synchronize();
|
||||
uint16_t sg = tmc2130_sg_meassure_stop();
|
||||
tmc2130_sg_meassure = 0xff;
|
||||
printf_P(PSTR("Meassure avg = %d\n"), sg);
|
||||
}
|
||||
}
|
||||
|
||||
void dcode_9125()
|
||||
{
|
||||
LOG("D9125 - PAT9125\n");
|
||||
if ((strchr_pointer[1+4] == '?') || (strchr_pointer[1+4] == 0))
|
||||
{
|
||||
printf("res_x=%d res_y=%d x=%d y=%d b=%d s=%d\n", pat9125_xres, pat9125_yres, pat9125_x, pat9125_y, pat9125_b, pat9125_s);
|
||||
return;
|
||||
}
|
||||
if (strchr_pointer[1+4] == '!')
|
||||
{
|
||||
pat9125_update();
|
||||
printf("x=%d y=%d b=%d s=%d\n", pat9125_x, pat9125_y, pat9125_b, pat9125_s);
|
||||
return;
|
||||
}
|
||||
if (code_seen('R'))
|
||||
{
|
||||
unsigned char res = (int)code_value();
|
||||
LOG("pat9125_init(xres=yres=%d)=%d\n", res, pat9125_init(res, res));
|
||||
}
|
||||
if (code_seen('X'))
|
||||
{
|
||||
pat9125_x = (int)code_value();
|
||||
LOG("pat9125_x=%d\n", pat9125_x);
|
||||
}
|
||||
if (code_seen('Y'))
|
||||
{
|
||||
pat9125_y = (int)code_value();
|
||||
LOG("pat9125_y=%d\n", pat9125_y);
|
||||
}
|
||||
if (code_seen('L'))
|
||||
{
|
||||
fsensor_log = (int)code_value();
|
||||
LOG("fsensor_log=%d\n", fsensor_log);
|
||||
}
|
||||
}
|
||||
|
||||
#endif //DEBUG_DCODES
|
22
Firmware/Dcodes.h
Normal file
22
Firmware/Dcodes.h
Normal file
|
@ -0,0 +1,22 @@
|
|||
#ifndef DCODES_H
|
||||
#define DCODES_H
|
||||
|
||||
extern void dcode__1(); //D-1 - Endless loop (to simulate deadlock)
|
||||
|
||||
extern void dcode_0(); //D0 - Reset
|
||||
extern void dcode_1(); //D1 - Clear EEPROM
|
||||
extern void dcode_2(); //D2 - Read/Write RAM
|
||||
extern void dcode_3(); //D3 - Read/Write EEPROM
|
||||
extern void dcode_4(); //D4 - Read/Write PIN
|
||||
extern void dcode_5(); //D5 - Read/Write FLASH
|
||||
extern void dcode_6(); //D6 - Read/Write external FLASH
|
||||
extern void dcode_7(); //D7 - Read/Write Bootloader
|
||||
extern void dcode_8(); //D8 - Read/Write PINDA
|
||||
|
||||
extern void dcode_10(); //D10 - XYZ calibration = OK
|
||||
extern void dcode_12(); //D12 - Reset failstat counters
|
||||
|
||||
extern void dcode_2130(); //D2130 - TMC2130
|
||||
extern void dcode_9125(); //D9125 - PAT9125
|
||||
|
||||
#endif //DCODES_H
|
14889
Firmware/Firmware.ino.rambo.hex
Normal file
14889
Firmware/Firmware.ino.rambo.hex
Normal file
File diff suppressed because it is too large
Load diff
|
@ -19,7 +19,7 @@
|
|||
// avrdude -F -v -pm168 -cstk500v1 -P\\.\COM4 -b19200 -D -Uflash:w:"file.hex":i
|
||||
// may need add path to avrdude config file: -C"c:\utils\arduino-0016\hardware\tools\avr\etc\avrdude.conf" if Arduino IDE installed in "c:\utils\arduino-0016\"
|
||||
// https://typeunsafe.wordpress.com/2011/07/22/programming-arduino-with-avrdude/
|
||||
"shell_cmd": "\"c:\\Program Files (x86)\\Arduino\\arduino_debug.exe\" --pref build.path=..\\output --upload --port COM6 --board marlinAddon:avr:rambo -v --preserve-temp-files Firmware.ino"
|
||||
"shell_cmd": "\"c:\\Program Files (x86)\\Arduino\\arduino_debug.exe\" --pref build.path=..\\output --upload --port COM9 --board marlinAddon:avr:rambo -v --preserve-temp-files Firmware.ino"
|
||||
},
|
||||
{
|
||||
"name": "map-data",
|
||||
|
|
|
@ -156,6 +156,8 @@ void LiquidCrystal::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) {
|
|||
command(LCD_ENTRYMODESET | _displaymode);
|
||||
delayMicroseconds(60);
|
||||
|
||||
_escape[0] = 0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -354,10 +356,149 @@ inline void LiquidCrystal::command(uint8_t value) {
|
|||
}
|
||||
|
||||
inline size_t LiquidCrystal::write(uint8_t value) {
|
||||
if (_escape[0] || (value == 0x1b))
|
||||
return escape_write(value);
|
||||
send(value, HIGH);
|
||||
return 1; // assume sucess
|
||||
}
|
||||
|
||||
//Supported VT100 escape codes:
|
||||
//EraseScreen "\x1b[2J"
|
||||
//CursorHome "\x1b[%d;%dH"
|
||||
//CursorShow "\x1b[?25h"
|
||||
//CursorHide "\x1b[?25l"
|
||||
|
||||
inline size_t LiquidCrystal::escape_write(uint8_t chr)
|
||||
{
|
||||
#define escape_cnt (_escape[0]) //escape character counter
|
||||
#define is_num_msk (_escape[1]) //numeric character bit mask
|
||||
#define chr_is_num (is_num_msk & 0x01) //current character is numeric
|
||||
#define e_2_is_num (is_num_msk & 0x04) //escape char 2 is numeric
|
||||
#define e_3_is_num (is_num_msk & 0x08) //...
|
||||
#define e_4_is_num (is_num_msk & 0x10)
|
||||
#define e_5_is_num (is_num_msk & 0x20)
|
||||
#define e_6_is_num (is_num_msk & 0x40)
|
||||
#define e_7_is_num (is_num_msk & 0x80)
|
||||
#define e2_num (_escape[2] - '0') //number from character 2
|
||||
#define e3_num (_escape[3] - '0') //number from character 3
|
||||
#define e23_num (10*e2_num+e3_num) //number from characters 2 and 3
|
||||
#define e4_num (_escape[4] - '0') //number from character 4
|
||||
#define e5_num (_escape[5] - '0') //number from character 5
|
||||
#define e45_num (10*e4_num+e5_num) //number from characters 4 and 5
|
||||
#define e6_num (_escape[6] - '0') //number from character 6
|
||||
#define e56_num (10*e5_num+e6_num) //number from characters 5 and 6
|
||||
if (escape_cnt > 1) // escape length > 1 = "\x1b["
|
||||
{
|
||||
_escape[escape_cnt] = chr; // store current char
|
||||
if ((chr >= '0') && (chr <= '9')) // char is numeric
|
||||
is_num_msk |= (1 | (1 << escape_cnt)); //set mask
|
||||
else
|
||||
is_num_msk &= ~1; //clear mask
|
||||
}
|
||||
switch (escape_cnt++)
|
||||
{
|
||||
case 0:
|
||||
if (chr == 0x1b) return 1; // escape = "\x1b"
|
||||
break;
|
||||
case 1:
|
||||
is_num_msk = 0x00; // reset 'is number' bit mask
|
||||
if (chr == '[') return 1; // escape = "\x1b["
|
||||
break;
|
||||
case 2:
|
||||
switch (chr)
|
||||
{
|
||||
case '2': return 1; // escape = "\x1b[2"
|
||||
case '?': return 1; // escape = "\x1b[?"
|
||||
default:
|
||||
if (chr_is_num) return 1; // escape = "\x1b[%1d"
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
switch (_escape[2])
|
||||
{
|
||||
case '?': // escape = "\x1b[?"
|
||||
if (chr == '2') return 1; // escape = "\x1b[?2"
|
||||
break;
|
||||
case '2':
|
||||
if (chr == 'J') // escape = "\x1b[2J"
|
||||
{ clear(); break; } // EraseScreen
|
||||
default:
|
||||
if (e_2_is_num && // escape = "\x1b[%1d"
|
||||
((chr == ';') || // escape = "\x1b[%1d;"
|
||||
chr_is_num)) // escape = "\x1b[%2d"
|
||||
return 1;
|
||||
}
|
||||
break;
|
||||
case 4:
|
||||
switch (_escape[2])
|
||||
{
|
||||
case '?': // "\x1b[?"
|
||||
if ((_escape[3] == '2') && (chr == '5')) return 1; // escape = "\x1b[?25"
|
||||
break;
|
||||
default:
|
||||
if (e_2_is_num) // escape = "\x1b[%1d"
|
||||
{
|
||||
if ((_escape[3] == ';') && chr_is_num) return 1; // escape = "\x1b[%1d;%1d"
|
||||
else if (e_3_is_num && (chr == ';')) return 1; // escape = "\x1b[%2d;"
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 5:
|
||||
switch (_escape[2])
|
||||
{
|
||||
case '?':
|
||||
if ((_escape[3] == '2') && (_escape[4] == '5')) // escape = "\x1b[?25"
|
||||
switch (chr)
|
||||
{
|
||||
case 'h': // escape = "\x1b[?25h"
|
||||
void cursor(); // CursorShow
|
||||
break;
|
||||
case 'l': // escape = "\x1b[?25l"
|
||||
noCursor(); // CursorHide
|
||||
break;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
if (e_2_is_num) // escape = "\x1b[%1d"
|
||||
{
|
||||
if ((_escape[3] == ';') && e_4_is_num) // escape = "\x1b%1d;%1dH"
|
||||
{
|
||||
if (chr == 'H') // escape = "\x1b%1d;%1dH"
|
||||
setCursor(e4_num, e2_num); // CursorHome
|
||||
else if (chr_is_num)
|
||||
return 1; // escape = "\x1b%1d;%2d"
|
||||
}
|
||||
else if (e_3_is_num && (_escape[4] == ';') && chr_is_num)
|
||||
return 1; // escape = "\x1b%2d;%1d"
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 6:
|
||||
if (e_2_is_num) // escape = "\x1b[%1d"
|
||||
{
|
||||
if ((_escape[3] == ';') && e_4_is_num && e_5_is_num && (chr == 'H')) // escape = "\x1b%1d;%2dH"
|
||||
setCursor(e45_num, e2_num); // CursorHome
|
||||
else if (e_3_is_num && (_escape[4] == ';') && e_5_is_num) // escape = "\x1b%2d;%1d"
|
||||
{
|
||||
if (chr == 'H') // escape = "\x1b%2d;%1dH"
|
||||
setCursor(e5_num, e23_num); // CursorHome
|
||||
else if (chr_is_num) // "\x1b%2d;%2d"
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 7:
|
||||
if (e_2_is_num && e_3_is_num && (_escape[4] == ';')) // "\x1b[%2d;"
|
||||
if (e_5_is_num && e_6_is_num && (chr == 'H')) // "\x1b[%2d;%2dH"
|
||||
setCursor(e56_num, e23_num); // CursorHome
|
||||
break;
|
||||
}
|
||||
escape_cnt = 0; // reset escape
|
||||
end:
|
||||
return 1; // assume sucess
|
||||
}
|
||||
|
||||
|
||||
/************ low level data pushing commands **********/
|
||||
|
||||
// write either command or data, with automatic 4/8-bit selection
|
||||
|
@ -402,4 +543,4 @@ void LiquidCrystal::write8bits(uint8_t value) {
|
|||
}
|
||||
|
||||
pulseEnable();
|
||||
}
|
||||
}
|
|
@ -103,6 +103,15 @@ private:
|
|||
uint8_t _initialized;
|
||||
|
||||
uint8_t _numlines,_currline;
|
||||
|
||||
uint8_t _escape[8];
|
||||
size_t escape_write(uint8_t value);
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
#define ESC_2J "\x1b[2J"
|
||||
#define ESC_25h "\x1b[?25h"
|
||||
#define ESC_25l "\x1b[?25l"
|
||||
#define ESC_H(c,r) "\x1b["#r";"#c"H"
|
||||
|
||||
#endif
|
|
@ -1,312 +1,427 @@
|
|||
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
// License: GPL
|
||||
|
||||
#ifndef MARLIN_H
|
||||
#define MARLIN_H
|
||||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
|
||||
#include <util/delay.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
|
||||
#include "fastio.h"
|
||||
#include "Configuration.h"
|
||||
#include "pins.h"
|
||||
|
||||
#ifndef AT90USB
|
||||
#define HardwareSerial_h // trick to disable the standard HWserial
|
||||
#endif
|
||||
|
||||
#if (ARDUINO >= 100)
|
||||
# include "Arduino.h"
|
||||
#else
|
||||
# include "WProgram.h"
|
||||
#endif
|
||||
|
||||
// Arduino < 1.0.0 does not define this, so we need to do it ourselves
|
||||
#ifndef analogInputToDigitalPin
|
||||
# define analogInputToDigitalPin(p) ((p) + A0)
|
||||
#endif
|
||||
|
||||
#ifdef AT90USB
|
||||
#include "HardwareSerial.h"
|
||||
#endif
|
||||
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
#ifndef cbi
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#endif
|
||||
#ifndef sbi
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif
|
||||
|
||||
#include "WString.h"
|
||||
|
||||
#ifdef AT90USB
|
||||
#ifdef BTENABLED
|
||||
#define MYSERIAL bt
|
||||
#else
|
||||
#define MYSERIAL Serial
|
||||
#endif // BTENABLED
|
||||
#else
|
||||
#define MYSERIAL MSerial
|
||||
#endif
|
||||
|
||||
#define SERIAL_PROTOCOL(x) (MYSERIAL.print(x))
|
||||
#define SERIAL_PROTOCOL_F(x,y) (MYSERIAL.print(x,y))
|
||||
#define SERIAL_PROTOCOLPGM(x) (serialprintPGM(PSTR(x)))
|
||||
#define SERIAL_PROTOCOLRPGM(x) (serialprintPGM((x)))
|
||||
#define SERIAL_PROTOCOLLN(x) (MYSERIAL.print(x),MYSERIAL.write('\n'))
|
||||
#define SERIAL_PROTOCOLLNPGM(x) (serialprintPGM(PSTR(x)),MYSERIAL.write('\n'))
|
||||
#define SERIAL_PROTOCOLLNRPGM(x) (serialprintPGM((x)),MYSERIAL.write('\n'))
|
||||
|
||||
|
||||
extern const char errormagic[] PROGMEM;
|
||||
extern const char echomagic[] PROGMEM;
|
||||
|
||||
#define SERIAL_ERROR_START (serialprintPGM(errormagic))
|
||||
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
|
||||
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
|
||||
#define SERIAL_ERRORRPGM(x) SERIAL_PROTOCOLRPGM(x)
|
||||
#define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x)
|
||||
#define SERIAL_ERRORLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
|
||||
#define SERIAL_ERRORLNRPGM(x) SERIAL_PROTOCOLLNRPGM(x)
|
||||
|
||||
#define SERIAL_ECHO_START (serialprintPGM(echomagic))
|
||||
#define SERIAL_ECHO(x) SERIAL_PROTOCOL(x)
|
||||
#define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x)
|
||||
#define SERIAL_ECHORPGM(x) SERIAL_PROTOCOLRPGM(x)
|
||||
#define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x)
|
||||
#define SERIAL_ECHOLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
|
||||
#define SERIAL_ECHOLNRPGM(x) SERIAL_PROTOCOLLNRPGM(x)
|
||||
|
||||
#define SERIAL_ECHOPAIR(name,value) (serial_echopair_P(PSTR(name),(value)))
|
||||
|
||||
void serial_echopair_P(const char *s_P, float v);
|
||||
void serial_echopair_P(const char *s_P, double v);
|
||||
void serial_echopair_P(const char *s_P, unsigned long v);
|
||||
|
||||
|
||||
//Things to write to serial from Program memory. Saves 400 to 2k of RAM.
|
||||
FORCE_INLINE void serialprintPGM(const char *str)
|
||||
{
|
||||
char ch=pgm_read_byte(str);
|
||||
while(ch)
|
||||
{
|
||||
MYSERIAL.write(ch);
|
||||
ch=pgm_read_byte(++str);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void get_command();
|
||||
void process_commands();
|
||||
|
||||
void manage_inactivity(bool ignore_stepper_queue=false);
|
||||
|
||||
#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
|
||||
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
||||
#define disable_x() { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
|
||||
#else
|
||||
#define enable_x() ;
|
||||
#define disable_x() ;
|
||||
#endif
|
||||
|
||||
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
#define enable_y() { WRITE(Y_ENABLE_PIN, Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, Y_ENABLE_ON); }
|
||||
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, !Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
|
||||
#else
|
||||
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
|
||||
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
|
||||
#endif
|
||||
#else
|
||||
#define enable_y() ;
|
||||
#define disable_y() ;
|
||||
#endif
|
||||
|
||||
#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; }
|
||||
#else
|
||||
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
||||
#define disable_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; }
|
||||
#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; }
|
||||
#endif
|
||||
#endif
|
||||
#else
|
||||
#define enable_z() ;
|
||||
#define disable_z() ;
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
//#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); }
|
||||
//#define disable_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; }
|
||||
//#endif
|
||||
//#else
|
||||
//#define enable_z() ;
|
||||
//#define disable_z() ;
|
||||
//#endif
|
||||
|
||||
|
||||
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
|
||||
#define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
|
||||
#define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
|
||||
#else
|
||||
#define enable_e0() /* nothing */
|
||||
#define disable_e0() /* nothing */
|
||||
#endif
|
||||
|
||||
#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
|
||||
#define enable_e1() WRITE(E1_ENABLE_PIN, E_ENABLE_ON)
|
||||
#define disable_e1() WRITE(E1_ENABLE_PIN,!E_ENABLE_ON)
|
||||
#else
|
||||
#define enable_e1() /* nothing */
|
||||
#define disable_e1() /* nothing */
|
||||
#endif
|
||||
|
||||
#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
|
||||
#define enable_e2() WRITE(E2_ENABLE_PIN, E_ENABLE_ON)
|
||||
#define disable_e2() WRITE(E2_ENABLE_PIN,!E_ENABLE_ON)
|
||||
#else
|
||||
#define enable_e2() /* nothing */
|
||||
#define disable_e2() /* nothing */
|
||||
#endif
|
||||
|
||||
|
||||
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
|
||||
|
||||
|
||||
void FlushSerialRequestResend();
|
||||
void ClearToSend();
|
||||
|
||||
void get_coordinates();
|
||||
void prepare_move();
|
||||
void kill(const char *full_screen_message = NULL);
|
||||
void Stop();
|
||||
|
||||
bool IsStopped();
|
||||
|
||||
//put an ASCII command at the end of the current buffer.
|
||||
void enquecommand(const char *cmd, bool from_progmem = false);
|
||||
//put an ASCII command at the end of the current buffer, read from flash
|
||||
#define enquecommand_P(cmd) enquecommand(cmd, true)
|
||||
void enquecommand_front(const char *cmd, bool from_progmem = false);
|
||||
//put an ASCII command at the end of the current buffer, read from flash
|
||||
#define enquecommand_P(cmd) enquecommand(cmd, true)
|
||||
#define enquecommand_front_P(cmd) enquecommand_front(cmd, true)
|
||||
void repeatcommand_front();
|
||||
|
||||
void prepare_arc_move(char isclockwise);
|
||||
void clamp_to_software_endstops(float target[3]);
|
||||
|
||||
void refresh_cmd_timeout(void);
|
||||
|
||||
#ifdef FAST_PWM_FAN
|
||||
void setPwmFrequency(uint8_t pin, int val);
|
||||
#endif
|
||||
|
||||
#ifndef CRITICAL_SECTION_START
|
||||
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||
#define CRITICAL_SECTION_END SREG = _sreg;
|
||||
#endif //CRITICAL_SECTION_START
|
||||
|
||||
extern float homing_feedrate[];
|
||||
extern bool axis_relative_modes[];
|
||||
extern int feedmultiply;
|
||||
extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
|
||||
extern bool volumetric_enabled;
|
||||
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
|
||||
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
|
||||
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
|
||||
extern float current_position[NUM_AXIS] ;
|
||||
extern float destination[NUM_AXIS] ;
|
||||
extern float add_homing[3];
|
||||
extern float min_pos[3];
|
||||
extern float max_pos[3];
|
||||
extern bool axis_known_position[3];
|
||||
extern float zprobe_zoffset;
|
||||
extern int fanSpeed;
|
||||
extern void homeaxis(int axis);
|
||||
|
||||
|
||||
#ifdef FAN_SOFT_PWM
|
||||
extern unsigned char fanSpeedSoftPwm;
|
||||
#endif
|
||||
|
||||
#ifdef FILAMENT_SENSOR
|
||||
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
|
||||
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
|
||||
extern float filament_width_meas; //holds the filament diameter as accurately measured
|
||||
extern signed char measurement_delay[]; //ring buffer to delay measurement
|
||||
extern int delay_index1, delay_index2; //index into ring buffer
|
||||
extern float delay_dist; //delay distance counter
|
||||
extern int meas_delay_cm; //delay distance
|
||||
#endif
|
||||
|
||||
#ifdef FWRETRACT
|
||||
extern bool autoretract_enabled;
|
||||
extern bool retracted[EXTRUDERS];
|
||||
extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift;
|
||||
extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate;
|
||||
#endif
|
||||
|
||||
extern unsigned long starttime;
|
||||
extern unsigned long stoptime;
|
||||
extern bool is_usb_printing;
|
||||
extern unsigned int usb_printing_counter;
|
||||
|
||||
extern unsigned long total_filament_used;
|
||||
void save_statistics(unsigned long _total_filament_used, unsigned long _total_print_time);
|
||||
extern unsigned int heating_status;
|
||||
extern unsigned int heating_status_counter;
|
||||
extern bool custom_message;
|
||||
extern unsigned int custom_message_type;
|
||||
extern unsigned int custom_message_state;
|
||||
|
||||
|
||||
// Handling multiple extruders pins
|
||||
extern uint8_t active_extruder;
|
||||
|
||||
#ifdef DIGIPOT_I2C
|
||||
extern void digipot_i2c_set_current( int channel, float current );
|
||||
extern void digipot_i2c_init();
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
extern void calculate_volumetric_multipliers();
|
||||
|
||||
// Similar to the default Arduino delay function,
|
||||
// but it keeps the background tasks running.
|
||||
extern void delay_keep_alive(int ms);
|
||||
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
// License: GPL
|
||||
|
||||
#ifndef MARLIN_H
|
||||
#define MARLIN_H
|
||||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
|
||||
#include <util/delay.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
|
||||
#include "fastio.h"
|
||||
#include "Configuration.h"
|
||||
#include "pins.h"
|
||||
|
||||
#ifndef AT90USB
|
||||
#define HardwareSerial_h // trick to disable the standard HWserial
|
||||
#endif
|
||||
|
||||
#if (ARDUINO >= 100)
|
||||
# include "Arduino.h"
|
||||
#else
|
||||
# include "WProgram.h"
|
||||
#endif
|
||||
|
||||
// Arduino < 1.0.0 does not define this, so we need to do it ourselves
|
||||
#ifndef analogInputToDigitalPin
|
||||
# define analogInputToDigitalPin(p) ((p) + A0)
|
||||
#endif
|
||||
|
||||
#ifdef AT90USB
|
||||
#include "HardwareSerial.h"
|
||||
#endif
|
||||
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
#ifndef cbi
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#endif
|
||||
#ifndef sbi
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif
|
||||
|
||||
#include "WString.h"
|
||||
|
||||
#ifdef AT90USB
|
||||
#ifdef BTENABLED
|
||||
#define MYSERIAL bt
|
||||
#else
|
||||
#define MYSERIAL Serial
|
||||
#endif // BTENABLED
|
||||
#else
|
||||
#define MYSERIAL MSerial
|
||||
#endif
|
||||
|
||||
extern FILE _lcdout;
|
||||
#define lcdout (&_lcdout)
|
||||
|
||||
extern FILE _uartout;
|
||||
#define uartout (&_uartout)
|
||||
|
||||
#define SERIAL_PROTOCOL(x) (MYSERIAL.print(x))
|
||||
#define SERIAL_PROTOCOL_F(x,y) (MYSERIAL.print(x,y))
|
||||
#define SERIAL_PROTOCOLPGM(x) (serialprintPGM(PSTR(x)))
|
||||
#define SERIAL_PROTOCOLRPGM(x) (serialprintPGM((x)))
|
||||
#define SERIAL_PROTOCOLLN(x) (MYSERIAL.print(x),MYSERIAL.write('\n'))
|
||||
#define SERIAL_PROTOCOLLNPGM(x) (serialprintPGM(PSTR(x)),MYSERIAL.write('\n'))
|
||||
#define SERIAL_PROTOCOLLNRPGM(x) (serialprintPGM((x)),MYSERIAL.write('\n'))
|
||||
|
||||
|
||||
extern const char errormagic[] PROGMEM;
|
||||
extern const char echomagic[] PROGMEM;
|
||||
|
||||
#define SERIAL_ERROR_START (serialprintPGM(errormagic))
|
||||
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
|
||||
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
|
||||
#define SERIAL_ERRORRPGM(x) SERIAL_PROTOCOLRPGM(x)
|
||||
#define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x)
|
||||
#define SERIAL_ERRORLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
|
||||
#define SERIAL_ERRORLNRPGM(x) SERIAL_PROTOCOLLNRPGM(x)
|
||||
|
||||
#define SERIAL_ECHO_START (serialprintPGM(echomagic))
|
||||
#define SERIAL_ECHO(x) SERIAL_PROTOCOL(x)
|
||||
#define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x)
|
||||
#define SERIAL_ECHORPGM(x) SERIAL_PROTOCOLRPGM(x)
|
||||
#define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x)
|
||||
#define SERIAL_ECHOLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
|
||||
#define SERIAL_ECHOLNRPGM(x) SERIAL_PROTOCOLLNRPGM(x)
|
||||
|
||||
#define SERIAL_ECHOPAIR(name,value) (serial_echopair_P(PSTR(name),(value)))
|
||||
|
||||
void serial_echopair_P(const char *s_P, float v);
|
||||
void serial_echopair_P(const char *s_P, double v);
|
||||
void serial_echopair_P(const char *s_P, unsigned long v);
|
||||
|
||||
|
||||
//Things to write to serial from Program memory. Saves 400 to 2k of RAM.
|
||||
FORCE_INLINE void serialprintPGM(const char *str)
|
||||
{
|
||||
char ch=pgm_read_byte(str);
|
||||
while(ch)
|
||||
{
|
||||
MYSERIAL.write(ch);
|
||||
ch=pgm_read_byte(++str);
|
||||
}
|
||||
}
|
||||
|
||||
bool is_buffer_empty();
|
||||
void get_command();
|
||||
void process_commands();
|
||||
void ramming();
|
||||
|
||||
void manage_inactivity(bool ignore_stepper_queue=false);
|
||||
|
||||
#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
|
||||
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
||||
#define disable_x() { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
|
||||
#else
|
||||
#define enable_x() ;
|
||||
#define disable_x() ;
|
||||
#endif
|
||||
|
||||
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
#define enable_y() { WRITE(Y_ENABLE_PIN, Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, Y_ENABLE_ON); }
|
||||
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, !Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
|
||||
#else
|
||||
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
|
||||
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
|
||||
#endif
|
||||
#else
|
||||
#define enable_y() ;
|
||||
#define disable_y() ;
|
||||
#endif
|
||||
|
||||
#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; }
|
||||
#else
|
||||
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
||||
#define disable_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; }
|
||||
#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; }
|
||||
#endif
|
||||
#endif
|
||||
#else
|
||||
#define enable_z() ;
|
||||
#define disable_z() ;
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
//#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); }
|
||||
//#define disable_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; }
|
||||
//#endif
|
||||
//#else
|
||||
//#define enable_z() ;
|
||||
//#define disable_z() ;
|
||||
//#endif
|
||||
|
||||
|
||||
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
|
||||
#define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
|
||||
#define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
|
||||
#else
|
||||
#define enable_e0() /* nothing */
|
||||
#define disable_e0() /* nothing */
|
||||
#endif
|
||||
|
||||
#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
|
||||
#define enable_e1() WRITE(E1_ENABLE_PIN, E_ENABLE_ON)
|
||||
#define disable_e1() WRITE(E1_ENABLE_PIN,!E_ENABLE_ON)
|
||||
#else
|
||||
#define enable_e1() /* nothing */
|
||||
#define disable_e1() /* nothing */
|
||||
#endif
|
||||
|
||||
#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
|
||||
#define enable_e2() WRITE(E2_ENABLE_PIN, E_ENABLE_ON)
|
||||
#define disable_e2() WRITE(E2_ENABLE_PIN,!E_ENABLE_ON)
|
||||
#else
|
||||
#define enable_e2() /* nothing */
|
||||
#define disable_e2() /* nothing */
|
||||
#endif
|
||||
|
||||
|
||||
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
|
||||
#define X_AXIS_MASK 1
|
||||
#define Y_AXIS_MASK 2
|
||||
#define Z_AXIS_MASK 4
|
||||
#define E_AXIS_MASK 8
|
||||
#define X_HEAD_MASK 16
|
||||
#define Y_HEAD_MASK 32
|
||||
|
||||
|
||||
void FlushSerialRequestResend();
|
||||
void ClearToSend();
|
||||
|
||||
void get_coordinates();
|
||||
void prepare_move();
|
||||
void kill(const char *full_screen_message = NULL, unsigned char id = 0);
|
||||
void Stop();
|
||||
|
||||
bool IsStopped();
|
||||
|
||||
//put an ASCII command at the end of the current buffer.
|
||||
void enquecommand(const char *cmd, bool from_progmem = false);
|
||||
//put an ASCII command at the end of the current buffer, read from flash
|
||||
#define enquecommand_P(cmd) enquecommand(cmd, true)
|
||||
void enquecommand_front(const char *cmd, bool from_progmem = false);
|
||||
//put an ASCII command at the end of the current buffer, read from flash
|
||||
#define enquecommand_P(cmd) enquecommand(cmd, true)
|
||||
#define enquecommand_front_P(cmd) enquecommand_front(cmd, true)
|
||||
void repeatcommand_front();
|
||||
// Remove all lines from the command queue.
|
||||
void cmdqueue_reset();
|
||||
|
||||
void prepare_arc_move(char isclockwise);
|
||||
void clamp_to_software_endstops(float target[3]);
|
||||
void refresh_cmd_timeout(void);
|
||||
|
||||
#ifdef FAST_PWM_FAN
|
||||
void setPwmFrequency(uint8_t pin, int val);
|
||||
#endif
|
||||
|
||||
#ifndef CRITICAL_SECTION_START
|
||||
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||
#define CRITICAL_SECTION_END SREG = _sreg;
|
||||
#endif //CRITICAL_SECTION_START
|
||||
|
||||
extern float homing_feedrate[];
|
||||
extern bool axis_relative_modes[];
|
||||
extern int feedmultiply;
|
||||
extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
|
||||
extern bool volumetric_enabled;
|
||||
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
|
||||
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
|
||||
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
|
||||
extern float current_position[NUM_AXIS] ;
|
||||
extern float destination[NUM_AXIS] ;
|
||||
extern float add_homing[3];
|
||||
extern float min_pos[3];
|
||||
extern float max_pos[3];
|
||||
extern bool axis_known_position[3];
|
||||
extern float zprobe_zoffset;
|
||||
extern int fanSpeed;
|
||||
extern void homeaxis(int axis);
|
||||
|
||||
|
||||
#ifdef FAN_SOFT_PWM
|
||||
extern unsigned char fanSpeedSoftPwm;
|
||||
#endif
|
||||
|
||||
#if defined(LCD_PWM_PIN) && (LCD_PWM_PIN > -1)
|
||||
extern unsigned char lcdSoftPwm;
|
||||
extern unsigned char lcdBlinkDelay;
|
||||
#endif
|
||||
|
||||
#ifdef FILAMENT_SENSOR
|
||||
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
|
||||
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
|
||||
extern float filament_width_meas; //holds the filament diameter as accurately measured
|
||||
extern signed char measurement_delay[]; //ring buffer to delay measurement
|
||||
extern int delay_index1, delay_index2; //index into ring buffer
|
||||
extern float delay_dist; //delay distance counter
|
||||
extern int meas_delay_cm; //delay distance
|
||||
#endif
|
||||
|
||||
#ifdef FWRETRACT
|
||||
extern bool autoretract_enabled;
|
||||
extern bool retracted[EXTRUDERS];
|
||||
extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift;
|
||||
extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate;
|
||||
#endif
|
||||
|
||||
#ifdef HOST_KEEPALIVE_FEATURE
|
||||
extern uint8_t host_keepalive_interval;
|
||||
#endif
|
||||
|
||||
extern unsigned long starttime;
|
||||
extern unsigned long stoptime;
|
||||
extern int bowden_length[4];
|
||||
extern bool is_usb_printing;
|
||||
extern bool homing_flag;
|
||||
extern bool temp_cal_active;
|
||||
extern bool loading_flag;
|
||||
extern unsigned int usb_printing_counter;
|
||||
|
||||
extern unsigned long kicktime;
|
||||
|
||||
extern unsigned long total_filament_used;
|
||||
void save_statistics(unsigned long _total_filament_used, unsigned long _total_print_time);
|
||||
extern unsigned int heating_status;
|
||||
extern unsigned int status_number;
|
||||
extern unsigned int heating_status_counter;
|
||||
extern bool custom_message;
|
||||
extern unsigned int custom_message_type;
|
||||
extern unsigned int custom_message_state;
|
||||
extern char snmm_filaments_used;
|
||||
extern unsigned long PingTime;
|
||||
|
||||
extern bool fan_state[2];
|
||||
extern int fan_edge_counter[2];
|
||||
extern int fan_speed[2];
|
||||
|
||||
// Handling multiple extruders pins
|
||||
extern uint8_t active_extruder;
|
||||
|
||||
#ifdef DIGIPOT_I2C
|
||||
extern void digipot_i2c_set_current( int channel, float current );
|
||||
extern void digipot_i2c_init();
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
//Long pause
|
||||
extern int saved_feedmultiply;
|
||||
extern float HotendTempBckp;
|
||||
extern int fanSpeedBckp;
|
||||
extern float pause_lastpos[4];
|
||||
extern unsigned long pause_time;
|
||||
extern unsigned long start_pause_print;
|
||||
extern unsigned long t_fan_rising_edge;
|
||||
|
||||
extern bool mesh_bed_leveling_flag;
|
||||
extern bool mesh_bed_run_from_menu;
|
||||
|
||||
extern float distance_from_min[2];
|
||||
|
||||
extern char dir_names[3][9];
|
||||
|
||||
extern void calculate_volumetric_multipliers();
|
||||
|
||||
// Similar to the default Arduino delay function,
|
||||
// but it keeps the background tasks running.
|
||||
extern void delay_keep_alive(unsigned int ms);
|
||||
|
||||
extern void check_babystep();
|
||||
|
||||
extern void long_pause();
|
||||
|
||||
#ifdef DIS
|
||||
|
||||
void d_setup();
|
||||
float d_ReadData();
|
||||
void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_points_num, float shift_x, float shift_y);
|
||||
|
||||
#endif
|
||||
float temp_comp_interpolation(float temperature);
|
||||
void temp_compensation_apply();
|
||||
void temp_compensation_start();
|
||||
|
||||
#ifdef PINDA_THERMISTOR
|
||||
float temp_compensation_pinda_thermistor_offset(float temperature_pinda);
|
||||
#endif //PINDA_THERMISTOR
|
||||
|
||||
void wait_for_heater(long codenum);
|
||||
void serialecho_temperatures();
|
||||
|
||||
void uvlo_();
|
||||
void recover_print(uint8_t automatic);
|
||||
void setup_uvlo_interrupt();
|
||||
void setup_fan_interrupt();
|
||||
|
||||
extern void recover_machine_state_after_power_panic();
|
||||
extern void restore_print_from_eeprom();
|
||||
extern void position_menu();
|
||||
|
||||
extern void print_world_coordinates();
|
||||
extern void print_physical_coordinates();
|
||||
extern void print_mesh_bed_leveling_table();
|
||||
|
||||
#ifdef HOST_KEEPALIVE_FEATURE
|
||||
|
||||
// States for managing Marlin and host communication
|
||||
// Marlin sends messages if blocked or busy
|
||||
/*enum MarlinBusyState {
|
||||
NOT_BUSY, // Not in a handler
|
||||
IN_HANDLER, // Processing a GCode
|
||||
IN_PROCESS, // Known to be blocking command input (as in G29)
|
||||
PAUSED_FOR_USER, // Blocking pending any input
|
||||
PAUSED_FOR_INPUT // Blocking pending text input (concept)
|
||||
};*/
|
||||
|
||||
#define NOT_BUSY 1
|
||||
#define IN_HANDLER 2
|
||||
#define IN_PROCESS 3
|
||||
#define PAUSED_FOR_USER 4
|
||||
#define PAUSED_FOR_INPUT 5
|
||||
|
||||
#define KEEPALIVE_STATE(n) do { busy_state = n;} while (0)
|
||||
extern void host_keepalive();
|
||||
//extern MarlinBusyState busy_state;
|
||||
extern int busy_state;
|
||||
|
||||
#endif //HOST_KEEPALIVE_FEATURE
|
||||
|
||||
// G-codes
|
||||
bool gcode_M45(bool onlyZ);
|
||||
void gcode_M701();
|
||||
|
||||
#define UVLO !(PINE & (1<<4))
|
||||
|
||||
void extr_unload2();
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#include "Marlin.h"
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
uint8_t selectedSerialPort = 0;
|
||||
|
||||
#ifndef AT90USB
|
||||
// this next line disables the entire HardwareSerial.cpp,
|
||||
// this is so I can support Attiny series and any other chip without a UART
|
||||
|
@ -56,14 +58,32 @@ FORCE_INLINE void store_char(unsigned char c)
|
|||
// Test for a framing error.
|
||||
if (M_UCSRxA & (1<<M_FEx)) {
|
||||
// Characters received with the framing errors will be ignored.
|
||||
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||
volatile unsigned char c = M_UDRx;
|
||||
// Dummy register read (discard)
|
||||
(void)(*(char *)M_UDRx);
|
||||
} else {
|
||||
// Read the input register.
|
||||
unsigned char c = M_UDRx;
|
||||
store_char(c);
|
||||
}
|
||||
}
|
||||
#ifndef SNMM
|
||||
SIGNAL(USART2_RX_vect)
|
||||
{
|
||||
if (selectedSerialPort == 1) {
|
||||
// Test for a framing error.
|
||||
if (UCSR2A & (1<<FE2)) {
|
||||
// Characters received with the framing errors will be ignored.
|
||||
// Dummy register read (discard)
|
||||
(void)(*(char *)UDR2);
|
||||
} else {
|
||||
// Read the input register.
|
||||
unsigned char c = UDR2;
|
||||
store_char(c);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
|
@ -88,7 +108,7 @@ void MarlinSerial::begin(long baud)
|
|||
useU2X = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// set up the first (original serial port)
|
||||
if (useU2X) {
|
||||
M_UCSRxA = 1 << M_U2Xx;
|
||||
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||
|
@ -104,13 +124,40 @@ void MarlinSerial::begin(long baud)
|
|||
sbi(M_UCSRxB, M_RXENx);
|
||||
sbi(M_UCSRxB, M_TXENx);
|
||||
sbi(M_UCSRxB, M_RXCIEx);
|
||||
|
||||
#ifndef SNMM
|
||||
|
||||
if (selectedSerialPort == 1) { //set up also the second serial port
|
||||
if (useU2X) {
|
||||
UCSR2A = 1 << U2X2;
|
||||
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||
} else {
|
||||
UCSR2A = 0;
|
||||
baud_setting = (F_CPU / 8 / baud - 1) / 2;
|
||||
}
|
||||
|
||||
// assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
|
||||
UBRR2H = baud_setting >> 8;
|
||||
UBRR2L = baud_setting;
|
||||
|
||||
sbi(UCSR2B, RXEN2);
|
||||
sbi(UCSR2B, TXEN2);
|
||||
sbi(UCSR2B, RXCIE2);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void MarlinSerial::end()
|
||||
{
|
||||
cbi(M_UCSRxB, M_RXENx);
|
||||
cbi(M_UCSRxB, M_TXENx);
|
||||
cbi(M_UCSRxB, M_RXCIEx);
|
||||
cbi(M_UCSRxB, M_RXCIEx);
|
||||
|
||||
#ifndef SNMM
|
||||
cbi(UCSR2B, RXEN2);
|
||||
cbi(UCSR2B, TXEN2);
|
||||
cbi(UCSR2B, RXCIE2);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -73,6 +73,7 @@
|
|||
// is the index of the location from which to read.
|
||||
#define RX_BUFFER_SIZE 128
|
||||
|
||||
extern uint8_t selectedSerialPort;
|
||||
|
||||
struct ring_buffer
|
||||
{
|
||||
|
@ -110,24 +111,48 @@ class MarlinSerial //: public Stream
|
|||
}
|
||||
|
||||
|
||||
FORCE_INLINE void checkRx(void)
|
||||
void checkRx(void)
|
||||
{
|
||||
if((M_UCSRxA & (1<<M_RXCx)) != 0) {
|
||||
// Test for a framing error.
|
||||
if (M_UCSRxA & (1<<M_FEx)) {
|
||||
// Characters received with the framing errors will be ignored.
|
||||
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||
volatile unsigned char c = M_UDRx;
|
||||
} else {
|
||||
unsigned char c = M_UDRx;
|
||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
||||
// if we should be storing the received character into the location
|
||||
// just before the tail (meaning that the head would advance to the
|
||||
// current location of the tail), we're about to overflow the buffer
|
||||
// and so we don't write the character or advance the head.
|
||||
if (i != rx_buffer.tail) {
|
||||
rx_buffer.buffer[rx_buffer.head] = c;
|
||||
rx_buffer.head = i;
|
||||
if (selectedSerialPort == 0) {
|
||||
if((M_UCSRxA & (1<<M_RXCx)) != 0) {
|
||||
// Test for a framing error.
|
||||
if (M_UCSRxA & (1<<M_FEx)) {
|
||||
// Characters received with the framing errors will be ignored.
|
||||
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||
volatile unsigned char c = M_UDRx;
|
||||
} else {
|
||||
unsigned char c = M_UDRx;
|
||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
||||
// if we should be storing the received character into the location
|
||||
// just before the tail (meaning that the head would advance to the
|
||||
// current location of the tail), we're about to overflow the buffer
|
||||
// and so we don't write the character or advance the head.
|
||||
if (i != rx_buffer.tail) {
|
||||
rx_buffer.buffer[rx_buffer.head] = c;
|
||||
rx_buffer.head = i;
|
||||
}
|
||||
selectedSerialPort = 0;
|
||||
}
|
||||
}
|
||||
} else if(selectedSerialPort == 1) {
|
||||
if((UCSR2A & (1<<RXC2)) != 0) {
|
||||
// Test for a framing error.
|
||||
if (UCSR2A & (1<<FE2)) {
|
||||
// Characters received with the framing errors will be ignored.
|
||||
// The temporary variable "c" was made volatile, so the compiler does not optimize this out.
|
||||
volatile unsigned char c = UDR2;
|
||||
} else {
|
||||
unsigned char c = UDR2;
|
||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
||||
// if we should be storing the received character into the location
|
||||
// just before the tail (meaning that the head would advance to the
|
||||
// current location of the tail), we're about to overflow the buffer
|
||||
// and so we don't write the character or advance the head.
|
||||
if (i != rx_buffer.tail) {
|
||||
rx_buffer.buffer[rx_buffer.head] = c;
|
||||
rx_buffer.head = i;
|
||||
}
|
||||
selectedSerialPort = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
File diff suppressed because it is too large
Load diff
1624
Firmware/Sd2Card.cpp
1624
Firmware/Sd2Card.cpp
File diff suppressed because it is too large
Load diff
|
@ -1,258 +1,262 @@
|
|||
/* Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino Sd2Card Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino Sd2Card Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef Sd2Card_h
|
||||
#define Sd2Card_h
|
||||
/**
|
||||
* \file
|
||||
* \brief Sd2Card class for V2 SD/SDHC cards
|
||||
*/
|
||||
#include "SdFatConfig.h"
|
||||
#include "Sd2PinMap.h"
|
||||
#include "SdInfo.h"
|
||||
//------------------------------------------------------------------------------
|
||||
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
|
||||
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_FULL_SPEED = 0;
|
||||
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_HALF_SPEED = 1;
|
||||
/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_QUARTER_SPEED = 2;
|
||||
/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_EIGHTH_SPEED = 3;
|
||||
/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_SIXTEENTH_SPEED = 4;
|
||||
//------------------------------------------------------------------------------
|
||||
/** init timeout ms */
|
||||
uint16_t const SD_INIT_TIMEOUT = 2000;
|
||||
/** erase timeout ms */
|
||||
uint16_t const SD_ERASE_TIMEOUT = 10000;
|
||||
/** read timeout ms */
|
||||
uint16_t const SD_READ_TIMEOUT = 300;
|
||||
/** write time out ms */
|
||||
uint16_t const SD_WRITE_TIMEOUT = 600;
|
||||
//------------------------------------------------------------------------------
|
||||
// SD card errors
|
||||
/** timeout error for command CMD0 (initialize card in SPI mode) */
|
||||
uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
|
||||
/** CMD8 was not accepted - not a valid SD card*/
|
||||
uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
|
||||
/** card returned an error response for CMD12 (write stop) */
|
||||
uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
|
||||
/** card returned an error response for CMD17 (read block) */
|
||||
uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
|
||||
/** card returned an error response for CMD18 (read multiple block) */
|
||||
uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
|
||||
/** card returned an error response for CMD24 (write block) */
|
||||
uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
|
||||
/** WRITE_MULTIPLE_BLOCKS command failed */
|
||||
uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
|
||||
/** card returned an error response for CMD58 (read OCR) */
|
||||
uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
|
||||
/** SET_WR_BLK_ERASE_COUNT failed */
|
||||
uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
|
||||
/** ACMD41 initialization process timeout */
|
||||
uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
|
||||
/** card returned a bad CSR version field */
|
||||
uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
|
||||
/** erase block group command failed */
|
||||
uint8_t const SD_CARD_ERROR_ERASE = 0XC;
|
||||
/** card not capable of single block erase */
|
||||
uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
|
||||
/** Erase sequence timed out */
|
||||
uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
|
||||
/** card returned an error token instead of read data */
|
||||
uint8_t const SD_CARD_ERROR_READ = 0XF;
|
||||
/** read CID or CSD failed */
|
||||
uint8_t const SD_CARD_ERROR_READ_REG = 0X10;
|
||||
/** timeout while waiting for start of read data */
|
||||
uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11;
|
||||
/** card did not accept STOP_TRAN_TOKEN */
|
||||
uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12;
|
||||
/** card returned an error token as a response to a write operation */
|
||||
uint8_t const SD_CARD_ERROR_WRITE = 0X13;
|
||||
/** attempt to write protected block zero */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14; // REMOVE - not used
|
||||
/** card did not go ready for a multiple block write */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15;
|
||||
/** card returned an error to a CMD13 status check after a write */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16;
|
||||
/** timeout occurred during write programming */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17;
|
||||
/** incorrect rate selected */
|
||||
uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18;
|
||||
/** init() not called */
|
||||
uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19;
|
||||
/** crc check error */
|
||||
uint8_t const SD_CARD_ERROR_CRC = 0X20;
|
||||
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const SD_CARD_ERROR_CMD48 = 0x80;
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const SD_CARD_ERROR_CMD49 = 0x81;
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
// card types
|
||||
/** Standard capacity V1 SD card */
|
||||
uint8_t const SD_CARD_TYPE_SD1 = 1;
|
||||
/** Standard capacity V2 SD card */
|
||||
uint8_t const SD_CARD_TYPE_SD2 = 2;
|
||||
/** High Capacity SD card */
|
||||
uint8_t const SD_CARD_TYPE_SDHC = 3;
|
||||
/**
|
||||
* define SOFTWARE_SPI to use bit-bang SPI
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
#if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
|
||||
#define SOFTWARE_SPI
|
||||
#elif USE_SOFTWARE_SPI
|
||||
#define SOFTWARE_SPI
|
||||
#endif // MEGA_SOFT_SPI
|
||||
//------------------------------------------------------------------------------
|
||||
// SPI pin definitions - do not edit here - change in SdFatConfig.h
|
||||
//
|
||||
#ifndef SOFTWARE_SPI
|
||||
// hardware pin defs
|
||||
/** The default chip select pin for the SD card is SS. */
|
||||
uint8_t const SD_CHIP_SELECT_PIN = SS_PIN;
|
||||
// The following three pins must not be redefined for hardware SPI.
|
||||
/** SPI Master Out Slave In pin */
|
||||
uint8_t const SPI_MOSI_PIN = MOSI_PIN;
|
||||
/** SPI Master In Slave Out pin */
|
||||
uint8_t const SPI_MISO_PIN = MISO_PIN;
|
||||
/** SPI Clock pin */
|
||||
uint8_t const SPI_SCK_PIN = SCK_PIN;
|
||||
|
||||
#else // SOFTWARE_SPI
|
||||
|
||||
/** SPI chip select pin */
|
||||
uint8_t const SD_CHIP_SELECT_PIN = SOFT_SPI_CS_PIN;
|
||||
/** SPI Master Out Slave In pin */
|
||||
uint8_t const SPI_MOSI_PIN = SOFT_SPI_MOSI_PIN;
|
||||
/** SPI Master In Slave Out pin */
|
||||
uint8_t const SPI_MISO_PIN = SOFT_SPI_MISO_PIN;
|
||||
/** SPI Clock pin */
|
||||
uint8_t const SPI_SCK_PIN = SOFT_SPI_SCK_PIN;
|
||||
#endif // SOFTWARE_SPI
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \class Sd2Card
|
||||
* \brief Raw access to SD and SDHC flash memory cards.
|
||||
*/
|
||||
class Sd2Card {
|
||||
public:
|
||||
/** Construct an instance of Sd2Card. */
|
||||
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
|
||||
uint32_t cardSize();
|
||||
bool erase(uint32_t firstBlock, uint32_t lastBlock);
|
||||
bool eraseSingleBlockEnable();
|
||||
/**
|
||||
* Set SD error code.
|
||||
* \param[in] code value for error code.
|
||||
*/
|
||||
void error(uint8_t code) {errorCode_ = code;}
|
||||
/**
|
||||
* \return error code for last error. See Sd2Card.h for a list of error codes.
|
||||
*/
|
||||
int errorCode() const {return errorCode_;}
|
||||
/** \return error data for last error. */
|
||||
int errorData() const {return status_;}
|
||||
/**
|
||||
* Initialize an SD flash memory card with default clock rate and chip
|
||||
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
|
||||
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
|
||||
bool readBlock(uint32_t block, uint8_t* dst);
|
||||
/**
|
||||
* Read a card's CID register. The CID contains card identification
|
||||
* information such as Manufacturer ID, Product name, Product serial
|
||||
* number and Manufacturing date.
|
||||
*
|
||||
* \param[out] cid pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCID(cid_t* cid) {
|
||||
return readRegister(CMD10, cid);
|
||||
}
|
||||
/**
|
||||
* Read a card's CSD register. The CSD contains Card-Specific Data that
|
||||
* provides information regarding access to the card's contents.
|
||||
*
|
||||
* \param[out] csd pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCSD(csd_t* csd) {
|
||||
return readRegister(CMD9, csd);
|
||||
}
|
||||
bool readData(uint8_t *dst);
|
||||
bool readStart(uint32_t blockNumber);
|
||||
bool readStop();
|
||||
bool setSckRate(uint8_t sckRateID);
|
||||
/** Return the card type: SD V1, SD V2 or SDHC
|
||||
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
|
||||
*/
|
||||
int type() const {return type_;}
|
||||
bool writeBlock(uint32_t blockNumber, const uint8_t* src);
|
||||
bool writeData(const uint8_t* src);
|
||||
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
|
||||
bool writeStop();
|
||||
|
||||
// Toshiba FlashAir support
|
||||
uint8_t readExtMemory(uint8_t mio, uint8_t func, uint32_t addr, uint16_t count, uint8_t* dst);
|
||||
|
||||
private:
|
||||
//----------------------------------------------------------------------------
|
||||
uint8_t chipSelectPin_;
|
||||
uint8_t errorCode_;
|
||||
uint8_t spiRate_;
|
||||
uint8_t status_;
|
||||
uint8_t type_;
|
||||
// private functions
|
||||
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
|
||||
cardCommand(CMD55, 0);
|
||||
return cardCommand(cmd, arg);
|
||||
}
|
||||
uint8_t cardCommand(uint8_t cmd, uint32_t arg);
|
||||
|
||||
bool readData(uint8_t* dst, uint16_t count);
|
||||
bool readRegister(uint8_t cmd, void* buf);
|
||||
void chipSelectHigh();
|
||||
void chipSelectLow();
|
||||
void type(uint8_t value) {type_ = value;}
|
||||
bool waitNotBusy(uint16_t timeoutMillis);
|
||||
bool writeData(uint8_t token, const uint8_t* src);
|
||||
|
||||
|
||||
// Toshiba FlashAir support
|
||||
uint8_t waitStartBlock(void);
|
||||
uint8_t readExt(uint32_t arg, uint8_t* dst, uint16_t count);
|
||||
};
|
||||
#endif // Sd2Card_h
|
||||
|
||||
|
||||
/* Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino Sd2Card Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino Sd2Card Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef Sd2Card_h
|
||||
#define Sd2Card_h
|
||||
/**
|
||||
* \file
|
||||
* \brief Sd2Card class for V2 SD/SDHC cards
|
||||
*/
|
||||
#include "SdFatConfig.h"
|
||||
#include "Sd2PinMap.h"
|
||||
#include "SdInfo.h"
|
||||
//------------------------------------------------------------------------------
|
||||
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
|
||||
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_FULL_SPEED = 0;
|
||||
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_HALF_SPEED = 1;
|
||||
/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_QUARTER_SPEED = 2;
|
||||
/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_EIGHTH_SPEED = 3;
|
||||
/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
|
||||
uint8_t const SPI_SIXTEENTH_SPEED = 4;
|
||||
//------------------------------------------------------------------------------
|
||||
/** init timeout ms */
|
||||
uint16_t const SD_INIT_TIMEOUT = 2000;
|
||||
/** erase timeout ms */
|
||||
uint16_t const SD_ERASE_TIMEOUT = 10000;
|
||||
/** read timeout ms */
|
||||
uint16_t const SD_READ_TIMEOUT = 300;
|
||||
/** write time out ms */
|
||||
uint16_t const SD_WRITE_TIMEOUT = 600;
|
||||
//------------------------------------------------------------------------------
|
||||
// SD card errors
|
||||
/** timeout error for command CMD0 (initialize card in SPI mode) */
|
||||
uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
|
||||
/** CMD8 was not accepted - not a valid SD card*/
|
||||
uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
|
||||
/** card returned an error response for CMD12 (write stop) */
|
||||
uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
|
||||
/** card returned an error response for CMD17 (read block) */
|
||||
uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
|
||||
/** card returned an error response for CMD18 (read multiple block) */
|
||||
uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
|
||||
/** card returned an error response for CMD24 (write block) */
|
||||
uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
|
||||
/** WRITE_MULTIPLE_BLOCKS command failed */
|
||||
uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
|
||||
/** card returned an error response for CMD58 (read OCR) */
|
||||
uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
|
||||
/** SET_WR_BLK_ERASE_COUNT failed */
|
||||
uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
|
||||
/** ACMD41 initialization process timeout */
|
||||
uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
|
||||
/** card returned a bad CSR version field */
|
||||
uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
|
||||
/** erase block group command failed */
|
||||
uint8_t const SD_CARD_ERROR_ERASE = 0XC;
|
||||
/** card not capable of single block erase */
|
||||
uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
|
||||
/** Erase sequence timed out */
|
||||
uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
|
||||
/** card returned an error token instead of read data */
|
||||
uint8_t const SD_CARD_ERROR_READ = 0XF;
|
||||
/** read CID or CSD failed */
|
||||
uint8_t const SD_CARD_ERROR_READ_REG = 0X10;
|
||||
/** timeout while waiting for start of read data */
|
||||
uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11;
|
||||
/** card did not accept STOP_TRAN_TOKEN */
|
||||
uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12;
|
||||
/** card returned an error token as a response to a write operation */
|
||||
uint8_t const SD_CARD_ERROR_WRITE = 0X13;
|
||||
/** attempt to write protected block zero */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14; // REMOVE - not used
|
||||
/** card did not go ready for a multiple block write */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15;
|
||||
/** card returned an error to a CMD13 status check after a write */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16;
|
||||
/** timeout occurred during write programming */
|
||||
uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17;
|
||||
/** incorrect rate selected */
|
||||
uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18;
|
||||
/** init() not called */
|
||||
uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19;
|
||||
/** crc check error */
|
||||
uint8_t const SD_CARD_ERROR_CRC = 0X20;
|
||||
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const SD_CARD_ERROR_CMD48 = 0x80;
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const SD_CARD_ERROR_CMD49 = 0x81;
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
// card types
|
||||
/** Standard capacity V1 SD card */
|
||||
uint8_t const SD_CARD_TYPE_SD1 = 1;
|
||||
/** Standard capacity V2 SD card */
|
||||
uint8_t const SD_CARD_TYPE_SD2 = 2;
|
||||
/** High Capacity SD card */
|
||||
uint8_t const SD_CARD_TYPE_SDHC = 3;
|
||||
/**
|
||||
* define SOFTWARE_SPI to use bit-bang SPI
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
#if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
|
||||
#define SOFTWARE_SPI
|
||||
#elif USE_SOFTWARE_SPI
|
||||
#define SOFTWARE_SPI
|
||||
#endif // MEGA_SOFT_SPI
|
||||
//------------------------------------------------------------------------------
|
||||
// SPI pin definitions - do not edit here - change in SdFatConfig.h
|
||||
//
|
||||
#ifndef SOFTWARE_SPI
|
||||
// hardware pin defs
|
||||
/** The default chip select pin for the SD card is SS. */
|
||||
uint8_t const SD_CHIP_SELECT_PIN = SS_PIN;
|
||||
// The following three pins must not be redefined for hardware SPI.
|
||||
/** SPI Master Out Slave In pin */
|
||||
uint8_t const SPI_MOSI_PIN = MOSI_PIN;
|
||||
/** SPI Master In Slave Out pin */
|
||||
uint8_t const SPI_MISO_PIN = MISO_PIN;
|
||||
/** SPI Clock pin */
|
||||
uint8_t const SPI_SCK_PIN = SCK_PIN;
|
||||
|
||||
#else // SOFTWARE_SPI
|
||||
|
||||
/** SPI chip select pin */
|
||||
uint8_t const SD_CHIP_SELECT_PIN = SOFT_SPI_CS_PIN;
|
||||
/** SPI Master Out Slave In pin */
|
||||
uint8_t const SPI_MOSI_PIN = SOFT_SPI_MOSI_PIN;
|
||||
/** SPI Master In Slave Out pin */
|
||||
uint8_t const SPI_MISO_PIN = SOFT_SPI_MISO_PIN;
|
||||
/** SPI Clock pin */
|
||||
uint8_t const SPI_SCK_PIN = SOFT_SPI_SCK_PIN;
|
||||
#endif // SOFTWARE_SPI
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \class Sd2Card
|
||||
* \brief Raw access to SD and SDHC flash memory cards.
|
||||
*/
|
||||
class Sd2Card {
|
||||
public:
|
||||
/** Construct an instance of Sd2Card. */
|
||||
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0), flash_air_compatible_(false) {}
|
||||
uint32_t cardSize();
|
||||
bool erase(uint32_t firstBlock, uint32_t lastBlock);
|
||||
bool eraseSingleBlockEnable();
|
||||
/**
|
||||
* Set SD error code.
|
||||
* \param[in] code value for error code.
|
||||
*/
|
||||
void error(uint8_t code) {errorCode_ = code;}
|
||||
/**
|
||||
* \return error code for last error. See Sd2Card.h for a list of error codes.
|
||||
*/
|
||||
int errorCode() const {return errorCode_;}
|
||||
/** \return error data for last error. */
|
||||
int errorData() const {return status_;}
|
||||
/**
|
||||
* Initialize an SD flash memory card with default clock rate and chip
|
||||
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
|
||||
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
|
||||
bool readBlock(uint32_t block, uint8_t* dst);
|
||||
/**
|
||||
* Read a card's CID register. The CID contains card identification
|
||||
* information such as Manufacturer ID, Product name, Product serial
|
||||
* number and Manufacturing date.
|
||||
*
|
||||
* \param[out] cid pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCID(cid_t* cid) {
|
||||
return readRegister(CMD10, cid);
|
||||
}
|
||||
/**
|
||||
* Read a card's CSD register. The CSD contains Card-Specific Data that
|
||||
* provides information regarding access to the card's contents.
|
||||
*
|
||||
* \param[out] csd pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCSD(csd_t* csd) {
|
||||
return readRegister(CMD9, csd);
|
||||
}
|
||||
bool readData(uint8_t *dst);
|
||||
bool readStart(uint32_t blockNumber);
|
||||
bool readStop();
|
||||
bool setSckRate(uint8_t sckRateID);
|
||||
/** Return the card type: SD V1, SD V2 or SDHC
|
||||
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
|
||||
*/
|
||||
int type() const {return type_;}
|
||||
bool writeBlock(uint32_t blockNumber, const uint8_t* src);
|
||||
bool writeData(const uint8_t* src);
|
||||
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
|
||||
bool writeStop();
|
||||
|
||||
// Toshiba FlashAir support
|
||||
uint8_t readExtMemory(uint8_t mio, uint8_t func, uint32_t addr, uint16_t count, uint8_t* dst);
|
||||
|
||||
void setFlashAirCompatible(bool flashAirCompatible) { flash_air_compatible_ = flashAirCompatible; }
|
||||
bool getFlashAirCompatible() const { return flash_air_compatible_; }
|
||||
|
||||
private:
|
||||
//----------------------------------------------------------------------------
|
||||
uint8_t chipSelectPin_;
|
||||
uint8_t errorCode_;
|
||||
uint8_t spiRate_;
|
||||
uint8_t status_;
|
||||
uint8_t type_;
|
||||
bool flash_air_compatible_;
|
||||
// private functions
|
||||
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
|
||||
cardCommand(CMD55, 0);
|
||||
return cardCommand(cmd, arg);
|
||||
}
|
||||
uint8_t cardCommand(uint8_t cmd, uint32_t arg);
|
||||
|
||||
bool readData(uint8_t* dst, uint16_t count);
|
||||
bool readRegister(uint8_t cmd, void* buf);
|
||||
void chipSelectHigh();
|
||||
void chipSelectLow();
|
||||
void type(uint8_t value) {type_ = value;}
|
||||
bool waitNotBusy(uint16_t timeoutMillis);
|
||||
bool writeData(uint8_t token, const uint8_t* src);
|
||||
|
||||
|
||||
// Toshiba FlashAir support
|
||||
uint8_t waitStartBlock(void);
|
||||
uint8_t readExt(uint32_t arg, uint8_t* dst, uint16_t count);
|
||||
};
|
||||
#endif // Sd2Card_h
|
||||
|
||||
|
||||
#endif
|
|
@ -1,368 +1,368 @@
|
|||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2010 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
// Warning this file was generated by a program.
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef Sd2PinMap_h
|
||||
#define Sd2PinMap_h
|
||||
#include <avr/io.h>
|
||||
//------------------------------------------------------------------------------
|
||||
/** struct for mapping digital pins */
|
||||
struct pin_map_t {
|
||||
volatile uint8_t* ddr;
|
||||
volatile uint8_t* pin;
|
||||
volatile uint8_t* port;
|
||||
uint8_t bit;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#if defined(__AVR_ATmega1280__)\
|
||||
|| defined(__AVR_ATmega2560__)
|
||||
// Mega
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 20; // D1
|
||||
uint8_t const SCL_PIN = 21; // D0
|
||||
|
||||
#undef MOSI_PIN
|
||||
#undef MISO_PIN
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 53; // B0
|
||||
uint8_t const MOSI_PIN = 51; // B2
|
||||
uint8_t const MISO_PIN = 50; // B3
|
||||
uint8_t const SCK_PIN = 52; // B1
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRE, &PINE, &PORTE, 0}, // E0 0
|
||||
{&DDRE, &PINE, &PORTE, 1}, // E1 1
|
||||
{&DDRE, &PINE, &PORTE, 4}, // E4 2
|
||||
{&DDRE, &PINE, &PORTE, 5}, // E5 3
|
||||
{&DDRG, &PING, &PORTG, 5}, // G5 4
|
||||
{&DDRE, &PINE, &PORTE, 3}, // E3 5
|
||||
{&DDRH, &PINH, &PORTH, 3}, // H3 6
|
||||
{&DDRH, &PINH, &PORTH, 4}, // H4 7
|
||||
{&DDRH, &PINH, &PORTH, 5}, // H5 8
|
||||
{&DDRH, &PINH, &PORTH, 6}, // H6 9
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 10
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 11
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 12
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 13
|
||||
{&DDRJ, &PINJ, &PORTJ, 1}, // J1 14
|
||||
{&DDRJ, &PINJ, &PORTJ, 0}, // J0 15
|
||||
{&DDRH, &PINH, &PORTH, 1}, // H1 16
|
||||
{&DDRH, &PINH, &PORTH, 0}, // H0 17
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 18
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 19
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 20
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 21
|
||||
{&DDRA, &PINA, &PORTA, 0}, // A0 22
|
||||
{&DDRA, &PINA, &PORTA, 1}, // A1 23
|
||||
{&DDRA, &PINA, &PORTA, 2}, // A2 24
|
||||
{&DDRA, &PINA, &PORTA, 3}, // A3 25
|
||||
{&DDRA, &PINA, &PORTA, 4}, // A4 26
|
||||
{&DDRA, &PINA, &PORTA, 5}, // A5 27
|
||||
{&DDRA, &PINA, &PORTA, 6}, // A6 28
|
||||
{&DDRA, &PINA, &PORTA, 7}, // A7 29
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 30
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 31
|
||||
{&DDRC, &PINC, &PORTC, 5}, // C5 32
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 33
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 34
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 35
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 36
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 37
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 38
|
||||
{&DDRG, &PING, &PORTG, 2}, // G2 39
|
||||
{&DDRG, &PING, &PORTG, 1}, // G1 40
|
||||
{&DDRG, &PING, &PORTG, 0}, // G0 41
|
||||
{&DDRL, &PINL, &PORTL, 7}, // L7 42
|
||||
{&DDRL, &PINL, &PORTL, 6}, // L6 43
|
||||
{&DDRL, &PINL, &PORTL, 5}, // L5 44
|
||||
{&DDRL, &PINL, &PORTL, 4}, // L4 45
|
||||
{&DDRL, &PINL, &PORTL, 3}, // L3 46
|
||||
{&DDRL, &PINL, &PORTL, 2}, // L2 47
|
||||
{&DDRL, &PINL, &PORTL, 1}, // L1 48
|
||||
{&DDRL, &PINL, &PORTL, 0}, // L0 49
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 50
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 51
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 52
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 53
|
||||
{&DDRF, &PINF, &PORTF, 0}, // F0 54
|
||||
{&DDRF, &PINF, &PORTF, 1}, // F1 55
|
||||
{&DDRF, &PINF, &PORTF, 2}, // F2 56
|
||||
{&DDRF, &PINF, &PORTF, 3}, // F3 57
|
||||
{&DDRF, &PINF, &PORTF, 4}, // F4 58
|
||||
{&DDRF, &PINF, &PORTF, 5}, // F5 59
|
||||
{&DDRF, &PINF, &PORTF, 6}, // F6 60
|
||||
{&DDRF, &PINF, &PORTF, 7}, // F7 61
|
||||
{&DDRK, &PINK, &PORTK, 0}, // K0 62
|
||||
{&DDRK, &PINK, &PORTK, 1}, // K1 63
|
||||
{&DDRK, &PINK, &PORTK, 2}, // K2 64
|
||||
{&DDRK, &PINK, &PORTK, 3}, // K3 65
|
||||
{&DDRK, &PINK, &PORTK, 4}, // K4 66
|
||||
{&DDRK, &PINK, &PORTK, 5}, // K5 67
|
||||
{&DDRK, &PINK, &PORTK, 6}, // K6 68
|
||||
{&DDRK, &PINK, &PORTK, 7} // K7 69
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_ATmega644P__)\
|
||||
|| defined(__AVR_ATmega644__)\
|
||||
|| defined(__AVR_ATmega1284P__)
|
||||
// Sanguino
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 17; // C1
|
||||
uint8_t const SCL_PIN = 18; // C2
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 4; // B4
|
||||
uint8_t const MOSI_PIN = 5; // B5
|
||||
uint8_t const MISO_PIN = 6; // B6
|
||||
uint8_t const SCK_PIN = 7; // B7
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 0
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 1
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 2
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 3
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 4
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 5
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 6
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 7
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 8
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 9
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 10
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 11
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 12
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 13
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 14
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 15
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 16
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 17
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 18
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 19
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 20
|
||||
{&DDRC, &PINC, &PORTC, 5}, // C5 21
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 22
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 23
|
||||
{&DDRA, &PINA, &PORTA, 7}, // A7 24
|
||||
{&DDRA, &PINA, &PORTA, 6}, // A6 25
|
||||
{&DDRA, &PINA, &PORTA, 5}, // A5 26
|
||||
{&DDRA, &PINA, &PORTA, 4}, // A4 27
|
||||
{&DDRA, &PINA, &PORTA, 3}, // A3 28
|
||||
{&DDRA, &PINA, &PORTA, 2}, // A2 29
|
||||
{&DDRA, &PINA, &PORTA, 1}, // A1 30
|
||||
{&DDRA, &PINA, &PORTA, 0} // A0 31
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_ATmega32U4__)
|
||||
// Teensy 2.0
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 6; // D1
|
||||
uint8_t const SCL_PIN = 5; // D0
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 0; // B0
|
||||
uint8_t const MOSI_PIN = 2; // B2
|
||||
uint8_t const MISO_PIN = 3; // B3
|
||||
uint8_t const SCK_PIN = 1; // B1
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 0
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 1
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 2
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 3
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 4
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 5
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 6
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 7
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 8
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 9
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 10
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 11
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 12
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 13
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 14
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 15
|
||||
{&DDRF, &PINF, &PORTF, 7}, // F7 16
|
||||
{&DDRF, &PINF, &PORTF, 6}, // F6 17
|
||||
{&DDRF, &PINF, &PORTF, 5}, // F5 18
|
||||
{&DDRF, &PINF, &PORTF, 4}, // F4 19
|
||||
{&DDRF, &PINF, &PORTF, 1}, // F1 20
|
||||
{&DDRF, &PINF, &PORTF, 0}, // F0 21
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 22
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 23
|
||||
{&DDRE, &PINE, &PORTE, 6} // E6 24
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_AT90USB646__)\
|
||||
|| defined(__AVR_AT90USB1286__)
|
||||
// Teensy++ 1.0 & 2.0
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 1; // D1
|
||||
uint8_t const SCL_PIN = 0; // D0
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 20; // B0
|
||||
uint8_t const MOSI_PIN = 22; // B2
|
||||
uint8_t const MISO_PIN = 23; // B3
|
||||
uint8_t const SCK_PIN = 21; // B1
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 0
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 1
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 2
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 3
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 4
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 5
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 6
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 7
|
||||
{&DDRE, &PINE, &PORTE, 0}, // E0 8
|
||||
{&DDRE, &PINE, &PORTE, 1}, // E1 9
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 10
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 11
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 12
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 13
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 14
|
||||
{&DDRC, &PINC, &PORTC, 5}, // C5 15
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 16
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 17
|
||||
{&DDRE, &PINE, &PORTE, 6}, // E6 18
|
||||
{&DDRE, &PINE, &PORTE, 7}, // E7 19
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 20
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 21
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 22
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 23
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 24
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 25
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 26
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 27
|
||||
{&DDRA, &PINA, &PORTA, 0}, // A0 28
|
||||
{&DDRA, &PINA, &PORTA, 1}, // A1 29
|
||||
{&DDRA, &PINA, &PORTA, 2}, // A2 30
|
||||
{&DDRA, &PINA, &PORTA, 3}, // A3 31
|
||||
{&DDRA, &PINA, &PORTA, 4}, // A4 32
|
||||
{&DDRA, &PINA, &PORTA, 5}, // A5 33
|
||||
{&DDRA, &PINA, &PORTA, 6}, // A6 34
|
||||
{&DDRA, &PINA, &PORTA, 7}, // A7 35
|
||||
{&DDRE, &PINE, &PORTE, 4}, // E4 36
|
||||
{&DDRE, &PINE, &PORTE, 5}, // E5 37
|
||||
{&DDRF, &PINF, &PORTF, 0}, // F0 38
|
||||
{&DDRF, &PINF, &PORTF, 1}, // F1 39
|
||||
{&DDRF, &PINF, &PORTF, 2}, // F2 40
|
||||
{&DDRF, &PINF, &PORTF, 3}, // F3 41
|
||||
{&DDRF, &PINF, &PORTF, 4}, // F4 42
|
||||
{&DDRF, &PINF, &PORTF, 5}, // F5 43
|
||||
{&DDRF, &PINF, &PORTF, 6}, // F6 44
|
||||
{&DDRF, &PINF, &PORTF, 7} // F7 45
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_ATmega168__)\
|
||||
||defined(__AVR_ATmega168P__)\
|
||||
||defined(__AVR_ATmega328P__)
|
||||
// 168 and 328 Arduinos
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 18; // C4
|
||||
uint8_t const SCL_PIN = 19; // C5
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 10; // B2
|
||||
uint8_t const MOSI_PIN = 11; // B3
|
||||
uint8_t const MISO_PIN = 12; // B4
|
||||
uint8_t const SCK_PIN = 13; // B5
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 0
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 1
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 2
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 3
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 4
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 5
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 6
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 7
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 8
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 9
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 10
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 11
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 12
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 13
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 14
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 15
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 16
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 17
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 18
|
||||
{&DDRC, &PINC, &PORTC, 5} // C5 19
|
||||
};
|
||||
#else // defined(__AVR_ATmega1280__)
|
||||
#error unknown chip
|
||||
#endif // defined(__AVR_ATmega1280__)
|
||||
//------------------------------------------------------------------------------
|
||||
static const uint8_t digitalPinCount = sizeof(digitalPinMap)/sizeof(pin_map_t);
|
||||
|
||||
uint8_t badPinNumber(void)
|
||||
__attribute__((error("Pin number is too large or not a constant")));
|
||||
|
||||
static inline __attribute__((always_inline))
|
||||
bool getPinMode(uint8_t pin) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
return (*digitalPinMap[pin].ddr >> digitalPinMap[pin].bit) & 1;
|
||||
} else {
|
||||
return badPinNumber();
|
||||
}
|
||||
}
|
||||
static inline __attribute__((always_inline))
|
||||
void setPinMode(uint8_t pin, uint8_t mode) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
if (mode) {
|
||||
*digitalPinMap[pin].ddr |= 1 << digitalPinMap[pin].bit;
|
||||
} else {
|
||||
*digitalPinMap[pin].ddr &= ~(1 << digitalPinMap[pin].bit);
|
||||
}
|
||||
} else {
|
||||
badPinNumber();
|
||||
}
|
||||
}
|
||||
static inline __attribute__((always_inline))
|
||||
bool fastDigitalRead(uint8_t pin) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
return (*digitalPinMap[pin].pin >> digitalPinMap[pin].bit) & 1;
|
||||
} else {
|
||||
return badPinNumber();
|
||||
}
|
||||
}
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalWrite(uint8_t pin, uint8_t value) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
if (value) {
|
||||
*digitalPinMap[pin].port |= 1 << digitalPinMap[pin].bit;
|
||||
} else {
|
||||
*digitalPinMap[pin].port &= ~(1 << digitalPinMap[pin].bit);
|
||||
}
|
||||
} else {
|
||||
badPinNumber();
|
||||
}
|
||||
}
|
||||
#endif // Sd2PinMap_h
|
||||
|
||||
|
||||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2010 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
// Warning this file was generated by a program.
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef Sd2PinMap_h
|
||||
#define Sd2PinMap_h
|
||||
#include <avr/io.h>
|
||||
//------------------------------------------------------------------------------
|
||||
/** struct for mapping digital pins */
|
||||
struct pin_map_t {
|
||||
volatile uint8_t* ddr;
|
||||
volatile uint8_t* pin;
|
||||
volatile uint8_t* port;
|
||||
uint8_t bit;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#if defined(__AVR_ATmega1280__)\
|
||||
|| defined(__AVR_ATmega2560__)
|
||||
// Mega
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 20; // D1
|
||||
uint8_t const SCL_PIN = 21; // D0
|
||||
|
||||
#undef MOSI_PIN
|
||||
#undef MISO_PIN
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 53; // B0
|
||||
uint8_t const MOSI_PIN = 51; // B2
|
||||
uint8_t const MISO_PIN = 50; // B3
|
||||
uint8_t const SCK_PIN = 52; // B1
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRE, &PINE, &PORTE, 0}, // E0 0
|
||||
{&DDRE, &PINE, &PORTE, 1}, // E1 1
|
||||
{&DDRE, &PINE, &PORTE, 4}, // E4 2
|
||||
{&DDRE, &PINE, &PORTE, 5}, // E5 3
|
||||
{&DDRG, &PING, &PORTG, 5}, // G5 4
|
||||
{&DDRE, &PINE, &PORTE, 3}, // E3 5
|
||||
{&DDRH, &PINH, &PORTH, 3}, // H3 6
|
||||
{&DDRH, &PINH, &PORTH, 4}, // H4 7
|
||||
{&DDRH, &PINH, &PORTH, 5}, // H5 8
|
||||
{&DDRH, &PINH, &PORTH, 6}, // H6 9
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 10
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 11
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 12
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 13
|
||||
{&DDRJ, &PINJ, &PORTJ, 1}, // J1 14
|
||||
{&DDRJ, &PINJ, &PORTJ, 0}, // J0 15
|
||||
{&DDRH, &PINH, &PORTH, 1}, // H1 16
|
||||
{&DDRH, &PINH, &PORTH, 0}, // H0 17
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 18
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 19
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 20
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 21
|
||||
{&DDRA, &PINA, &PORTA, 0}, // A0 22
|
||||
{&DDRA, &PINA, &PORTA, 1}, // A1 23
|
||||
{&DDRA, &PINA, &PORTA, 2}, // A2 24
|
||||
{&DDRA, &PINA, &PORTA, 3}, // A3 25
|
||||
{&DDRA, &PINA, &PORTA, 4}, // A4 26
|
||||
{&DDRA, &PINA, &PORTA, 5}, // A5 27
|
||||
{&DDRA, &PINA, &PORTA, 6}, // A6 28
|
||||
{&DDRA, &PINA, &PORTA, 7}, // A7 29
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 30
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 31
|
||||
{&DDRC, &PINC, &PORTC, 5}, // C5 32
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 33
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 34
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 35
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 36
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 37
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 38
|
||||
{&DDRG, &PING, &PORTG, 2}, // G2 39
|
||||
{&DDRG, &PING, &PORTG, 1}, // G1 40
|
||||
{&DDRG, &PING, &PORTG, 0}, // G0 41
|
||||
{&DDRL, &PINL, &PORTL, 7}, // L7 42
|
||||
{&DDRL, &PINL, &PORTL, 6}, // L6 43
|
||||
{&DDRL, &PINL, &PORTL, 5}, // L5 44
|
||||
{&DDRL, &PINL, &PORTL, 4}, // L4 45
|
||||
{&DDRL, &PINL, &PORTL, 3}, // L3 46
|
||||
{&DDRL, &PINL, &PORTL, 2}, // L2 47
|
||||
{&DDRL, &PINL, &PORTL, 1}, // L1 48
|
||||
{&DDRL, &PINL, &PORTL, 0}, // L0 49
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 50
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 51
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 52
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 53
|
||||
{&DDRF, &PINF, &PORTF, 0}, // F0 54
|
||||
{&DDRF, &PINF, &PORTF, 1}, // F1 55
|
||||
{&DDRF, &PINF, &PORTF, 2}, // F2 56
|
||||
{&DDRF, &PINF, &PORTF, 3}, // F3 57
|
||||
{&DDRF, &PINF, &PORTF, 4}, // F4 58
|
||||
{&DDRF, &PINF, &PORTF, 5}, // F5 59
|
||||
{&DDRF, &PINF, &PORTF, 6}, // F6 60
|
||||
{&DDRF, &PINF, &PORTF, 7}, // F7 61
|
||||
{&DDRK, &PINK, &PORTK, 0}, // K0 62
|
||||
{&DDRK, &PINK, &PORTK, 1}, // K1 63
|
||||
{&DDRK, &PINK, &PORTK, 2}, // K2 64
|
||||
{&DDRK, &PINK, &PORTK, 3}, // K3 65
|
||||
{&DDRK, &PINK, &PORTK, 4}, // K4 66
|
||||
{&DDRK, &PINK, &PORTK, 5}, // K5 67
|
||||
{&DDRK, &PINK, &PORTK, 6}, // K6 68
|
||||
{&DDRK, &PINK, &PORTK, 7} // K7 69
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_ATmega644P__)\
|
||||
|| defined(__AVR_ATmega644__)\
|
||||
|| defined(__AVR_ATmega1284P__)
|
||||
// Sanguino
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 17; // C1
|
||||
uint8_t const SCL_PIN = 18; // C2
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 4; // B4
|
||||
uint8_t const MOSI_PIN = 5; // B5
|
||||
uint8_t const MISO_PIN = 6; // B6
|
||||
uint8_t const SCK_PIN = 7; // B7
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 0
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 1
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 2
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 3
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 4
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 5
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 6
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 7
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 8
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 9
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 10
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 11
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 12
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 13
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 14
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 15
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 16
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 17
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 18
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 19
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 20
|
||||
{&DDRC, &PINC, &PORTC, 5}, // C5 21
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 22
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 23
|
||||
{&DDRA, &PINA, &PORTA, 7}, // A7 24
|
||||
{&DDRA, &PINA, &PORTA, 6}, // A6 25
|
||||
{&DDRA, &PINA, &PORTA, 5}, // A5 26
|
||||
{&DDRA, &PINA, &PORTA, 4}, // A4 27
|
||||
{&DDRA, &PINA, &PORTA, 3}, // A3 28
|
||||
{&DDRA, &PINA, &PORTA, 2}, // A2 29
|
||||
{&DDRA, &PINA, &PORTA, 1}, // A1 30
|
||||
{&DDRA, &PINA, &PORTA, 0} // A0 31
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_ATmega32U4__)
|
||||
// Teensy 2.0
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 6; // D1
|
||||
uint8_t const SCL_PIN = 5; // D0
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 0; // B0
|
||||
uint8_t const MOSI_PIN = 2; // B2
|
||||
uint8_t const MISO_PIN = 3; // B3
|
||||
uint8_t const SCK_PIN = 1; // B1
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 0
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 1
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 2
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 3
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 4
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 5
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 6
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 7
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 8
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 9
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 10
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 11
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 12
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 13
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 14
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 15
|
||||
{&DDRF, &PINF, &PORTF, 7}, // F7 16
|
||||
{&DDRF, &PINF, &PORTF, 6}, // F6 17
|
||||
{&DDRF, &PINF, &PORTF, 5}, // F5 18
|
||||
{&DDRF, &PINF, &PORTF, 4}, // F4 19
|
||||
{&DDRF, &PINF, &PORTF, 1}, // F1 20
|
||||
{&DDRF, &PINF, &PORTF, 0}, // F0 21
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 22
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 23
|
||||
{&DDRE, &PINE, &PORTE, 6} // E6 24
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_AT90USB646__)\
|
||||
|| defined(__AVR_AT90USB1286__)
|
||||
// Teensy++ 1.0 & 2.0
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 1; // D1
|
||||
uint8_t const SCL_PIN = 0; // D0
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 20; // B0
|
||||
uint8_t const MOSI_PIN = 22; // B2
|
||||
uint8_t const MISO_PIN = 23; // B3
|
||||
uint8_t const SCK_PIN = 21; // B1
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 0
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 1
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 2
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 3
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 4
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 5
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 6
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 7
|
||||
{&DDRE, &PINE, &PORTE, 0}, // E0 8
|
||||
{&DDRE, &PINE, &PORTE, 1}, // E1 9
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 10
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 11
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 12
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 13
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 14
|
||||
{&DDRC, &PINC, &PORTC, 5}, // C5 15
|
||||
{&DDRC, &PINC, &PORTC, 6}, // C6 16
|
||||
{&DDRC, &PINC, &PORTC, 7}, // C7 17
|
||||
{&DDRE, &PINE, &PORTE, 6}, // E6 18
|
||||
{&DDRE, &PINE, &PORTE, 7}, // E7 19
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 20
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 21
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 22
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 23
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 24
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 25
|
||||
{&DDRB, &PINB, &PORTB, 6}, // B6 26
|
||||
{&DDRB, &PINB, &PORTB, 7}, // B7 27
|
||||
{&DDRA, &PINA, &PORTA, 0}, // A0 28
|
||||
{&DDRA, &PINA, &PORTA, 1}, // A1 29
|
||||
{&DDRA, &PINA, &PORTA, 2}, // A2 30
|
||||
{&DDRA, &PINA, &PORTA, 3}, // A3 31
|
||||
{&DDRA, &PINA, &PORTA, 4}, // A4 32
|
||||
{&DDRA, &PINA, &PORTA, 5}, // A5 33
|
||||
{&DDRA, &PINA, &PORTA, 6}, // A6 34
|
||||
{&DDRA, &PINA, &PORTA, 7}, // A7 35
|
||||
{&DDRE, &PINE, &PORTE, 4}, // E4 36
|
||||
{&DDRE, &PINE, &PORTE, 5}, // E5 37
|
||||
{&DDRF, &PINF, &PORTF, 0}, // F0 38
|
||||
{&DDRF, &PINF, &PORTF, 1}, // F1 39
|
||||
{&DDRF, &PINF, &PORTF, 2}, // F2 40
|
||||
{&DDRF, &PINF, &PORTF, 3}, // F3 41
|
||||
{&DDRF, &PINF, &PORTF, 4}, // F4 42
|
||||
{&DDRF, &PINF, &PORTF, 5}, // F5 43
|
||||
{&DDRF, &PINF, &PORTF, 6}, // F6 44
|
||||
{&DDRF, &PINF, &PORTF, 7} // F7 45
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#elif defined(__AVR_ATmega168__)\
|
||||
||defined(__AVR_ATmega168P__)\
|
||||
||defined(__AVR_ATmega328P__)
|
||||
// 168 and 328 Arduinos
|
||||
|
||||
// Two Wire (aka I2C) ports
|
||||
uint8_t const SDA_PIN = 18; // C4
|
||||
uint8_t const SCL_PIN = 19; // C5
|
||||
|
||||
// SPI port
|
||||
uint8_t const SS_PIN = 10; // B2
|
||||
uint8_t const MOSI_PIN = 11; // B3
|
||||
uint8_t const MISO_PIN = 12; // B4
|
||||
uint8_t const SCK_PIN = 13; // B5
|
||||
|
||||
static const pin_map_t digitalPinMap[] = {
|
||||
{&DDRD, &PIND, &PORTD, 0}, // D0 0
|
||||
{&DDRD, &PIND, &PORTD, 1}, // D1 1
|
||||
{&DDRD, &PIND, &PORTD, 2}, // D2 2
|
||||
{&DDRD, &PIND, &PORTD, 3}, // D3 3
|
||||
{&DDRD, &PIND, &PORTD, 4}, // D4 4
|
||||
{&DDRD, &PIND, &PORTD, 5}, // D5 5
|
||||
{&DDRD, &PIND, &PORTD, 6}, // D6 6
|
||||
{&DDRD, &PIND, &PORTD, 7}, // D7 7
|
||||
{&DDRB, &PINB, &PORTB, 0}, // B0 8
|
||||
{&DDRB, &PINB, &PORTB, 1}, // B1 9
|
||||
{&DDRB, &PINB, &PORTB, 2}, // B2 10
|
||||
{&DDRB, &PINB, &PORTB, 3}, // B3 11
|
||||
{&DDRB, &PINB, &PORTB, 4}, // B4 12
|
||||
{&DDRB, &PINB, &PORTB, 5}, // B5 13
|
||||
{&DDRC, &PINC, &PORTC, 0}, // C0 14
|
||||
{&DDRC, &PINC, &PORTC, 1}, // C1 15
|
||||
{&DDRC, &PINC, &PORTC, 2}, // C2 16
|
||||
{&DDRC, &PINC, &PORTC, 3}, // C3 17
|
||||
{&DDRC, &PINC, &PORTC, 4}, // C4 18
|
||||
{&DDRC, &PINC, &PORTC, 5} // C5 19
|
||||
};
|
||||
#else // defined(__AVR_ATmega1280__)
|
||||
#error unknown chip
|
||||
#endif // defined(__AVR_ATmega1280__)
|
||||
//------------------------------------------------------------------------------
|
||||
static const uint8_t digitalPinCount = sizeof(digitalPinMap)/sizeof(pin_map_t);
|
||||
|
||||
uint8_t badPinNumber(void)
|
||||
__attribute__((error("Pin number is too large or not a constant")));
|
||||
|
||||
static inline __attribute__((always_inline))
|
||||
bool getPinMode(uint8_t pin) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
return (*digitalPinMap[pin].ddr >> digitalPinMap[pin].bit) & 1;
|
||||
} else {
|
||||
return badPinNumber();
|
||||
}
|
||||
}
|
||||
static inline __attribute__((always_inline))
|
||||
void setPinMode(uint8_t pin, uint8_t mode) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
if (mode) {
|
||||
*digitalPinMap[pin].ddr |= 1 << digitalPinMap[pin].bit;
|
||||
} else {
|
||||
*digitalPinMap[pin].ddr &= ~(1 << digitalPinMap[pin].bit);
|
||||
}
|
||||
} else {
|
||||
badPinNumber();
|
||||
}
|
||||
}
|
||||
static inline __attribute__((always_inline))
|
||||
bool fastDigitalRead(uint8_t pin) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
return (*digitalPinMap[pin].pin >> digitalPinMap[pin].bit) & 1;
|
||||
} else {
|
||||
return badPinNumber();
|
||||
}
|
||||
}
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalWrite(uint8_t pin, uint8_t value) {
|
||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||
if (value) {
|
||||
*digitalPinMap[pin].port |= 1 << digitalPinMap[pin].bit;
|
||||
} else {
|
||||
*digitalPinMap[pin].port &= ~(1 << digitalPinMap[pin].bit);
|
||||
}
|
||||
} else {
|
||||
badPinNumber();
|
||||
}
|
||||
}
|
||||
#endif // Sd2PinMap_h
|
||||
|
||||
|
||||
#endif
|
|
@ -294,7 +294,7 @@ bool SdBaseFile::getFilename(char* name) {
|
|||
return true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdBaseFile::getpos(fpos_t* pos) {
|
||||
void SdBaseFile::getpos(filepos_t* pos) {
|
||||
pos->position = curPosition_;
|
||||
pos->cluster = curCluster_;
|
||||
}
|
||||
|
@ -925,7 +925,7 @@ bool SdBaseFile::openRoot(SdVolume* vol) {
|
|||
* \return The byte if no error and not at eof else -1;
|
||||
*/
|
||||
int SdBaseFile::peek() {
|
||||
fpos_t pos;
|
||||
filepos_t pos;
|
||||
getpos(&pos);
|
||||
int c = read();
|
||||
if (c >= 0) setpos(&pos);
|
||||
|
@ -1492,7 +1492,7 @@ bool SdBaseFile::seekSet(uint32_t pos) {
|
|||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdBaseFile::setpos(fpos_t* pos) {
|
||||
void SdBaseFile::setpos(filepos_t* pos) {
|
||||
curPosition_ = pos->position;
|
||||
curCluster_ = pos->cluster;
|
||||
}
|
||||
|
|
|
@ -31,16 +31,16 @@
|
|||
#include "SdVolume.h"
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct fpos_t
|
||||
* \struct filepos_t
|
||||
* \brief internal type for istream
|
||||
* do not use in user apps
|
||||
*/
|
||||
struct fpos_t {
|
||||
struct filepos_t {
|
||||
/** stream position */
|
||||
uint32_t position;
|
||||
/** cluster for position */
|
||||
uint32_t cluster;
|
||||
fpos_t() : position(0), cluster(0) {}
|
||||
filepos_t() : position(0), cluster(0) {}
|
||||
};
|
||||
|
||||
// use the gnu style oflag in open()
|
||||
|
@ -196,11 +196,11 @@ class SdBaseFile {
|
|||
/** get position for streams
|
||||
* \param[out] pos struct to receive position
|
||||
*/
|
||||
void getpos(fpos_t* pos);
|
||||
void getpos(filepos_t* pos);
|
||||
/** set position for streams
|
||||
* \param[out] pos struct with value for new position
|
||||
*/
|
||||
void setpos(fpos_t* pos);
|
||||
void setpos(filepos_t* pos);
|
||||
//----------------------------------------------------------------------------
|
||||
bool close();
|
||||
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
|
||||
|
|
|
@ -44,6 +44,34 @@ int SdFatUtil::FreeRam() {
|
|||
}
|
||||
#endif // __arm
|
||||
|
||||
void SdFatUtil::set_stack_guard()
|
||||
{
|
||||
char i = 0;
|
||||
uint32_t *stack_guard;
|
||||
|
||||
stack_guard = (uint32_t*)&__bss_end;
|
||||
//for (i = 0; i < 10; i++) {
|
||||
*stack_guard = STACK_GUARD_TEST_VALUE;
|
||||
//}
|
||||
}
|
||||
|
||||
bool SdFatUtil::test_stack_integrity()
|
||||
{
|
||||
uint32_t* stack_guard = (uint32_t*)&__bss_end;
|
||||
return (*stack_guard == STACK_GUARD_TEST_VALUE);
|
||||
}
|
||||
|
||||
uint32_t SdFatUtil::get_stack_guard_test_value()
|
||||
{
|
||||
//static char i = 0;
|
||||
uint32_t* stack_guard;
|
||||
uint32_t output;
|
||||
stack_guard = (uint32_t*)&__bss_end;
|
||||
//output = *(stack_guard + i);
|
||||
//i++;
|
||||
output = *stack_guard;
|
||||
return(output);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** %Print a string in flash memory.
|
||||
*
|
||||
|
|
|
@ -1,48 +1,51 @@
|
|||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2008 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef SdFatUtil_h
|
||||
#define SdFatUtil_h
|
||||
/**
|
||||
* \file
|
||||
* \brief Useful utility functions.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#include "MarlinSerial.h"
|
||||
/** Store and print a string in flash memory.*/
|
||||
#define PgmPrint(x) SerialPrint_P(PSTR(x))
|
||||
/** Store and print a string in flash memory followed by a CR/LF.*/
|
||||
#define PgmPrintln(x) SerialPrintln_P(PSTR(x))
|
||||
|
||||
namespace SdFatUtil {
|
||||
int FreeRam();
|
||||
void print_P( PGM_P str);
|
||||
void println_P( PGM_P str);
|
||||
void SerialPrint_P(PGM_P str);
|
||||
void SerialPrintln_P(PGM_P str);
|
||||
}
|
||||
|
||||
using namespace SdFatUtil; // NOLINT
|
||||
#endif // #define SdFatUtil_h
|
||||
|
||||
|
||||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2008 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef SdFatUtil_h
|
||||
#define SdFatUtil_h
|
||||
/**
|
||||
* \file
|
||||
* \brief Useful utility functions.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#include "MarlinSerial.h"
|
||||
/** Store and print a string in flash memory.*/
|
||||
#define PgmPrint(x) SerialPrint_P(PSTR(x))
|
||||
/** Store and print a string in flash memory followed by a CR/LF.*/
|
||||
#define PgmPrintln(x) SerialPrintln_P(PSTR(x))
|
||||
|
||||
namespace SdFatUtil {
|
||||
int FreeRam();
|
||||
void print_P( PGM_P str);
|
||||
void println_P( PGM_P str);
|
||||
void SerialPrint_P(PGM_P str);
|
||||
void SerialPrintln_P(PGM_P str);
|
||||
void set_stack_guard();
|
||||
bool test_stack_integrity();
|
||||
uint32_t get_stack_guard_test_value();
|
||||
}
|
||||
|
||||
using namespace SdFatUtil; // NOLINT
|
||||
#endif // #define SdFatUtil_h
|
||||
|
||||
|
||||
#endif
|
|
@ -1,95 +1,95 @@
|
|||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
|
||||
#ifdef SDSUPPORT
|
||||
#include "SdFile.h"
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
|
||||
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
|
||||
*/
|
||||
SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write data to an open file.
|
||||
*
|
||||
* \note Data is moved to the cache but may not be written to the
|
||||
* storage device until sync() is called.
|
||||
*
|
||||
* \param[in] buf Pointer to the location of the data to be written.
|
||||
*
|
||||
* \param[in] nbyte Number of bytes to write.
|
||||
*
|
||||
* \return For success write() returns the number of bytes written, always
|
||||
* \a nbyte. If an error occurs, write() returns -1. Possible errors
|
||||
* include write() is called before a file has been opened, write is called
|
||||
* for a read-only file, device is full, a corrupt file system or an I/O error.
|
||||
*
|
||||
*/
|
||||
int16_t SdFile::write(const void* buf, uint16_t nbyte) {
|
||||
return SdBaseFile::write(buf, nbyte);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a byte to a file. Required by the Arduino Print class.
|
||||
* \param[in] b the byte to be written.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
#if ARDUINO >= 100
|
||||
size_t SdFile::write(uint8_t b)
|
||||
{
|
||||
return SdBaseFile::write(&b, 1);
|
||||
}
|
||||
#else
|
||||
void SdFile::write(uint8_t b)
|
||||
{
|
||||
SdBaseFile::write(&b, 1);
|
||||
}
|
||||
#endif
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a string to a file. Used by the Arduino Print class.
|
||||
* \param[in] str Pointer to the string.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
void SdFile::write(const char* str) {
|
||||
SdBaseFile::write(str, strlen(str));
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a PROGMEM string to a file.
|
||||
* \param[in] str Pointer to the PROGMEM string.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
void SdFile::write_P(PGM_P str) {
|
||||
for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a PROGMEM string followed by CR/LF to a file.
|
||||
* \param[in] str Pointer to the PROGMEM string.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
void SdFile::writeln_P(PGM_P str) {
|
||||
write_P(str);
|
||||
write_P(PSTR("\r\n"));
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
|
||||
#ifdef SDSUPPORT
|
||||
#include "SdFile.h"
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
|
||||
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
|
||||
*/
|
||||
SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write data to an open file.
|
||||
*
|
||||
* \note Data is moved to the cache but may not be written to the
|
||||
* storage device until sync() is called.
|
||||
*
|
||||
* \param[in] buf Pointer to the location of the data to be written.
|
||||
*
|
||||
* \param[in] nbyte Number of bytes to write.
|
||||
*
|
||||
* \return For success write() returns the number of bytes written, always
|
||||
* \a nbyte. If an error occurs, write() returns -1. Possible errors
|
||||
* include write() is called before a file has been opened, write is called
|
||||
* for a read-only file, device is full, a corrupt file system or an I/O error.
|
||||
*
|
||||
*/
|
||||
int16_t SdFile::write(const void* buf, uint16_t nbyte) {
|
||||
return SdBaseFile::write(buf, nbyte);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a byte to a file. Required by the Arduino Print class.
|
||||
* \param[in] b the byte to be written.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
#if ARDUINO >= 100
|
||||
size_t SdFile::write(uint8_t b)
|
||||
{
|
||||
return SdBaseFile::write(&b, 1);
|
||||
}
|
||||
#else
|
||||
void SdFile::write(uint8_t b)
|
||||
{
|
||||
SdBaseFile::write(&b, 1);
|
||||
}
|
||||
#endif
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a string to a file. Used by the Arduino Print class.
|
||||
* \param[in] str Pointer to the string.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
void SdFile::write(const char* str) {
|
||||
SdBaseFile::write(str, strlen(str));
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a PROGMEM string to a file.
|
||||
* \param[in] str Pointer to the PROGMEM string.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
void SdFile::write_P(PGM_P str) {
|
||||
for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write a PROGMEM string followed by CR/LF to a file.
|
||||
* \param[in] str Pointer to the PROGMEM string.
|
||||
* Use writeError to check for errors.
|
||||
*/
|
||||
void SdFile::writeln_P(PGM_P str) {
|
||||
write_P(str);
|
||||
write_P(PSTR("\r\n"));
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
|
|
@ -1,286 +1,286 @@
|
|||
/* Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino Sd2Card Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino Sd2Card Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef SdInfo_h
|
||||
#define SdInfo_h
|
||||
#include <stdint.h>
|
||||
// Based on the document:
|
||||
//
|
||||
// SD Specifications
|
||||
// Part 1
|
||||
// Physical Layer
|
||||
// Simplified Specification
|
||||
// Version 3.01
|
||||
// May 18, 2010
|
||||
//
|
||||
// http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
|
||||
//------------------------------------------------------------------------------
|
||||
// SD card commands
|
||||
/** GO_IDLE_STATE - init card in spi mode if CS low */
|
||||
uint8_t const CMD0 = 0X00;
|
||||
/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
|
||||
uint8_t const CMD8 = 0X08;
|
||||
/** SEND_CSD - read the Card Specific Data (CSD register) */
|
||||
uint8_t const CMD9 = 0X09;
|
||||
/** SEND_CID - read the card identification information (CID register) */
|
||||
uint8_t const CMD10 = 0X0A;
|
||||
/** STOP_TRANSMISSION - end multiple block read sequence */
|
||||
uint8_t const CMD12 = 0X0C;
|
||||
/** SEND_STATUS - read the card status register */
|
||||
uint8_t const CMD13 = 0X0D;
|
||||
/** READ_SINGLE_BLOCK - read a single data block from the card */
|
||||
uint8_t const CMD17 = 0X11;
|
||||
/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
|
||||
uint8_t const CMD18 = 0X12;
|
||||
/** WRITE_BLOCK - write a single data block to the card */
|
||||
uint8_t const CMD24 = 0X18;
|
||||
/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
|
||||
uint8_t const CMD25 = 0X19;
|
||||
/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
|
||||
uint8_t const CMD32 = 0X20;
|
||||
/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
|
||||
range to be erased*/
|
||||
uint8_t const CMD33 = 0X21;
|
||||
/** ERASE - erase all previously selected blocks */
|
||||
uint8_t const CMD38 = 0X26;
|
||||
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const CMD48 = 0x30;
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const CMD49 = 0x31;
|
||||
|
||||
/** APP_CMD - escape for application specific command */
|
||||
uint8_t const CMD55 = 0X37;
|
||||
/** READ_OCR - read the OCR register of a card */
|
||||
uint8_t const CMD58 = 0X3A;
|
||||
/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
|
||||
pre-erased before writing */
|
||||
uint8_t const ACMD23 = 0X17;
|
||||
/** SD_SEND_OP_COMD - Sends host capacity support information and
|
||||
activates the card's initialization process */
|
||||
uint8_t const ACMD41 = 0X29;
|
||||
//------------------------------------------------------------------------------
|
||||
/** status for card in the ready state */
|
||||
uint8_t const R1_READY_STATE = 0X00;
|
||||
/** status for card in the idle state */
|
||||
uint8_t const R1_IDLE_STATE = 0X01;
|
||||
/** status bit for illegal command */
|
||||
uint8_t const R1_ILLEGAL_COMMAND = 0X04;
|
||||
/** start data token for read or write single block*/
|
||||
uint8_t const DATA_START_BLOCK = 0XFE;
|
||||
/** stop token for write multiple blocks*/
|
||||
uint8_t const STOP_TRAN_TOKEN = 0XFD;
|
||||
/** start data token for write multiple blocks*/
|
||||
uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC;
|
||||
/** mask for data response tokens after a write block operation */
|
||||
uint8_t const DATA_RES_MASK = 0X1F;
|
||||
/** write data accepted token */
|
||||
uint8_t const DATA_RES_ACCEPTED = 0X05;
|
||||
//------------------------------------------------------------------------------
|
||||
/** Card IDentification (CID) register */
|
||||
typedef struct CID {
|
||||
// byte 0
|
||||
/** Manufacturer ID */
|
||||
unsigned char mid;
|
||||
// byte 1-2
|
||||
/** OEM/Application ID */
|
||||
char oid[2];
|
||||
// byte 3-7
|
||||
/** Product name */
|
||||
char pnm[5];
|
||||
// byte 8
|
||||
/** Product revision least significant digit */
|
||||
unsigned char prv_m : 4;
|
||||
/** Product revision most significant digit */
|
||||
unsigned char prv_n : 4;
|
||||
// byte 9-12
|
||||
/** Product serial number */
|
||||
uint32_t psn;
|
||||
// byte 13
|
||||
/** Manufacturing date year low digit */
|
||||
unsigned char mdt_year_high : 4;
|
||||
/** not used */
|
||||
unsigned char reserved : 4;
|
||||
// byte 14
|
||||
/** Manufacturing date month */
|
||||
unsigned char mdt_month : 4;
|
||||
/** Manufacturing date year low digit */
|
||||
unsigned char mdt_year_low :4;
|
||||
// byte 15
|
||||
/** not used always 1 */
|
||||
unsigned char always1 : 1;
|
||||
/** CRC7 checksum */
|
||||
unsigned char crc : 7;
|
||||
}cid_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** CSD for version 1.00 cards */
|
||||
typedef struct CSDV1 {
|
||||
// byte 0
|
||||
unsigned char reserved1 : 6;
|
||||
unsigned char csd_ver : 2;
|
||||
// byte 1
|
||||
unsigned char taac;
|
||||
// byte 2
|
||||
unsigned char nsac;
|
||||
// byte 3
|
||||
unsigned char tran_speed;
|
||||
// byte 4
|
||||
unsigned char ccc_high;
|
||||
// byte 5
|
||||
unsigned char read_bl_len : 4;
|
||||
unsigned char ccc_low : 4;
|
||||
// byte 6
|
||||
unsigned char c_size_high : 2;
|
||||
unsigned char reserved2 : 2;
|
||||
unsigned char dsr_imp : 1;
|
||||
unsigned char read_blk_misalign :1;
|
||||
unsigned char write_blk_misalign : 1;
|
||||
unsigned char read_bl_partial : 1;
|
||||
// byte 7
|
||||
unsigned char c_size_mid;
|
||||
// byte 8
|
||||
unsigned char vdd_r_curr_max : 3;
|
||||
unsigned char vdd_r_curr_min : 3;
|
||||
unsigned char c_size_low :2;
|
||||
// byte 9
|
||||
unsigned char c_size_mult_high : 2;
|
||||
unsigned char vdd_w_cur_max : 3;
|
||||
unsigned char vdd_w_curr_min : 3;
|
||||
// byte 10
|
||||
unsigned char sector_size_high : 6;
|
||||
unsigned char erase_blk_en : 1;
|
||||
unsigned char c_size_mult_low : 1;
|
||||
// byte 11
|
||||
unsigned char wp_grp_size : 7;
|
||||
unsigned char sector_size_low : 1;
|
||||
// byte 12
|
||||
unsigned char write_bl_len_high : 2;
|
||||
unsigned char r2w_factor : 3;
|
||||
unsigned char reserved3 : 2;
|
||||
unsigned char wp_grp_enable : 1;
|
||||
// byte 13
|
||||
unsigned char reserved4 : 5;
|
||||
unsigned char write_partial : 1;
|
||||
unsigned char write_bl_len_low : 2;
|
||||
// byte 14
|
||||
unsigned char reserved5: 2;
|
||||
unsigned char file_format : 2;
|
||||
unsigned char tmp_write_protect : 1;
|
||||
unsigned char perm_write_protect : 1;
|
||||
unsigned char copy : 1;
|
||||
/** Indicates the file format on the card */
|
||||
unsigned char file_format_grp : 1;
|
||||
// byte 15
|
||||
unsigned char always1 : 1;
|
||||
unsigned char crc : 7;
|
||||
}csd1_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** CSD for version 2.00 cards */
|
||||
typedef struct CSDV2 {
|
||||
// byte 0
|
||||
unsigned char reserved1 : 6;
|
||||
unsigned char csd_ver : 2;
|
||||
// byte 1
|
||||
/** fixed to 0X0E */
|
||||
unsigned char taac;
|
||||
// byte 2
|
||||
/** fixed to 0 */
|
||||
unsigned char nsac;
|
||||
// byte 3
|
||||
unsigned char tran_speed;
|
||||
// byte 4
|
||||
unsigned char ccc_high;
|
||||
// byte 5
|
||||
/** This field is fixed to 9h, which indicates READ_BL_LEN=512 Byte */
|
||||
unsigned char read_bl_len : 4;
|
||||
unsigned char ccc_low : 4;
|
||||
// byte 6
|
||||
/** not used */
|
||||
unsigned char reserved2 : 4;
|
||||
unsigned char dsr_imp : 1;
|
||||
/** fixed to 0 */
|
||||
unsigned char read_blk_misalign :1;
|
||||
/** fixed to 0 */
|
||||
unsigned char write_blk_misalign : 1;
|
||||
/** fixed to 0 - no partial read */
|
||||
unsigned char read_bl_partial : 1;
|
||||
// byte 7
|
||||
/** not used */
|
||||
unsigned char reserved3 : 2;
|
||||
/** high part of card size */
|
||||
unsigned char c_size_high : 6;
|
||||
// byte 8
|
||||
/** middle part of card size */
|
||||
unsigned char c_size_mid;
|
||||
// byte 9
|
||||
/** low part of card size */
|
||||
unsigned char c_size_low;
|
||||
// byte 10
|
||||
/** sector size is fixed at 64 KB */
|
||||
unsigned char sector_size_high : 6;
|
||||
/** fixed to 1 - erase single is supported */
|
||||
unsigned char erase_blk_en : 1;
|
||||
/** not used */
|
||||
unsigned char reserved4 : 1;
|
||||
// byte 11
|
||||
unsigned char wp_grp_size : 7;
|
||||
/** sector size is fixed at 64 KB */
|
||||
unsigned char sector_size_low : 1;
|
||||
// byte 12
|
||||
/** write_bl_len fixed for 512 byte blocks */
|
||||
unsigned char write_bl_len_high : 2;
|
||||
/** fixed value of 2 */
|
||||
unsigned char r2w_factor : 3;
|
||||
/** not used */
|
||||
unsigned char reserved5 : 2;
|
||||
/** fixed value of 0 - no write protect groups */
|
||||
unsigned char wp_grp_enable : 1;
|
||||
// byte 13
|
||||
unsigned char reserved6 : 5;
|
||||
/** always zero - no partial block read*/
|
||||
unsigned char write_partial : 1;
|
||||
/** write_bl_len fixed for 512 byte blocks */
|
||||
unsigned char write_bl_len_low : 2;
|
||||
// byte 14
|
||||
unsigned char reserved7: 2;
|
||||
/** Do not use always 0 */
|
||||
unsigned char file_format : 2;
|
||||
unsigned char tmp_write_protect : 1;
|
||||
unsigned char perm_write_protect : 1;
|
||||
unsigned char copy : 1;
|
||||
/** Do not use always 0 */
|
||||
unsigned char file_format_grp : 1;
|
||||
// byte 15
|
||||
/** not used always 1 */
|
||||
unsigned char always1 : 1;
|
||||
/** checksum */
|
||||
unsigned char crc : 7;
|
||||
}csd2_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** union of old and new style CSD register */
|
||||
union csd_t {
|
||||
csd1_t v1;
|
||||
csd2_t v2;
|
||||
};
|
||||
#endif // SdInfo_h
|
||||
|
||||
/* Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino Sd2Card Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino Sd2Card Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#ifndef SdInfo_h
|
||||
#define SdInfo_h
|
||||
#include <stdint.h>
|
||||
// Based on the document:
|
||||
//
|
||||
// SD Specifications
|
||||
// Part 1
|
||||
// Physical Layer
|
||||
// Simplified Specification
|
||||
// Version 3.01
|
||||
// May 18, 2010
|
||||
//
|
||||
// http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
|
||||
//------------------------------------------------------------------------------
|
||||
// SD card commands
|
||||
/** GO_IDLE_STATE - init card in spi mode if CS low */
|
||||
uint8_t const CMD0 = 0X00;
|
||||
/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
|
||||
uint8_t const CMD8 = 0X08;
|
||||
/** SEND_CSD - read the Card Specific Data (CSD register) */
|
||||
uint8_t const CMD9 = 0X09;
|
||||
/** SEND_CID - read the card identification information (CID register) */
|
||||
uint8_t const CMD10 = 0X0A;
|
||||
/** STOP_TRANSMISSION - end multiple block read sequence */
|
||||
uint8_t const CMD12 = 0X0C;
|
||||
/** SEND_STATUS - read the card status register */
|
||||
uint8_t const CMD13 = 0X0D;
|
||||
/** READ_SINGLE_BLOCK - read a single data block from the card */
|
||||
uint8_t const CMD17 = 0X11;
|
||||
/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
|
||||
uint8_t const CMD18 = 0X12;
|
||||
/** WRITE_BLOCK - write a single data block to the card */
|
||||
uint8_t const CMD24 = 0X18;
|
||||
/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
|
||||
uint8_t const CMD25 = 0X19;
|
||||
/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
|
||||
uint8_t const CMD32 = 0X20;
|
||||
/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
|
||||
range to be erased*/
|
||||
uint8_t const CMD33 = 0X21;
|
||||
/** ERASE - erase all previously selected blocks */
|
||||
uint8_t const CMD38 = 0X26;
|
||||
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const CMD48 = 0x30;
|
||||
/** Toshiba FlashAir: iSDIO */
|
||||
uint8_t const CMD49 = 0x31;
|
||||
|
||||
/** APP_CMD - escape for application specific command */
|
||||
uint8_t const CMD55 = 0X37;
|
||||
/** READ_OCR - read the OCR register of a card */
|
||||
uint8_t const CMD58 = 0X3A;
|
||||
/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
|
||||
pre-erased before writing */
|
||||
uint8_t const ACMD23 = 0X17;
|
||||
/** SD_SEND_OP_COMD - Sends host capacity support information and
|
||||
activates the card's initialization process */
|
||||
uint8_t const ACMD41 = 0X29;
|
||||
//------------------------------------------------------------------------------
|
||||
/** status for card in the ready state */
|
||||
uint8_t const R1_READY_STATE = 0X00;
|
||||
/** status for card in the idle state */
|
||||
uint8_t const R1_IDLE_STATE = 0X01;
|
||||
/** status bit for illegal command */
|
||||
uint8_t const R1_ILLEGAL_COMMAND = 0X04;
|
||||
/** start data token for read or write single block*/
|
||||
uint8_t const DATA_START_BLOCK = 0XFE;
|
||||
/** stop token for write multiple blocks*/
|
||||
uint8_t const STOP_TRAN_TOKEN = 0XFD;
|
||||
/** start data token for write multiple blocks*/
|
||||
uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC;
|
||||
/** mask for data response tokens after a write block operation */
|
||||
uint8_t const DATA_RES_MASK = 0X1F;
|
||||
/** write data accepted token */
|
||||
uint8_t const DATA_RES_ACCEPTED = 0X05;
|
||||
//------------------------------------------------------------------------------
|
||||
/** Card IDentification (CID) register */
|
||||
typedef struct CID {
|
||||
// byte 0
|
||||
/** Manufacturer ID */
|
||||
unsigned char mid;
|
||||
// byte 1-2
|
||||
/** OEM/Application ID */
|
||||
char oid[2];
|
||||
// byte 3-7
|
||||
/** Product name */
|
||||
char pnm[5];
|
||||
// byte 8
|
||||
/** Product revision least significant digit */
|
||||
unsigned char prv_m : 4;
|
||||
/** Product revision most significant digit */
|
||||
unsigned char prv_n : 4;
|
||||
// byte 9-12
|
||||
/** Product serial number */
|
||||
uint32_t psn;
|
||||
// byte 13
|
||||
/** Manufacturing date year low digit */
|
||||
unsigned char mdt_year_high : 4;
|
||||
/** not used */
|
||||
unsigned char reserved : 4;
|
||||
// byte 14
|
||||
/** Manufacturing date month */
|
||||
unsigned char mdt_month : 4;
|
||||
/** Manufacturing date year low digit */
|
||||
unsigned char mdt_year_low :4;
|
||||
// byte 15
|
||||
/** not used always 1 */
|
||||
unsigned char always1 : 1;
|
||||
/** CRC7 checksum */
|
||||
unsigned char crc : 7;
|
||||
}cid_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** CSD for version 1.00 cards */
|
||||
typedef struct CSDV1 {
|
||||
// byte 0
|
||||
unsigned char reserved1 : 6;
|
||||
unsigned char csd_ver : 2;
|
||||
// byte 1
|
||||
unsigned char taac;
|
||||
// byte 2
|
||||
unsigned char nsac;
|
||||
// byte 3
|
||||
unsigned char tran_speed;
|
||||
// byte 4
|
||||
unsigned char ccc_high;
|
||||
// byte 5
|
||||
unsigned char read_bl_len : 4;
|
||||
unsigned char ccc_low : 4;
|
||||
// byte 6
|
||||
unsigned char c_size_high : 2;
|
||||
unsigned char reserved2 : 2;
|
||||
unsigned char dsr_imp : 1;
|
||||
unsigned char read_blk_misalign :1;
|
||||
unsigned char write_blk_misalign : 1;
|
||||
unsigned char read_bl_partial : 1;
|
||||
// byte 7
|
||||
unsigned char c_size_mid;
|
||||
// byte 8
|
||||
unsigned char vdd_r_curr_max : 3;
|
||||
unsigned char vdd_r_curr_min : 3;
|
||||
unsigned char c_size_low :2;
|
||||
// byte 9
|
||||
unsigned char c_size_mult_high : 2;
|
||||
unsigned char vdd_w_cur_max : 3;
|
||||
unsigned char vdd_w_curr_min : 3;
|
||||
// byte 10
|
||||
unsigned char sector_size_high : 6;
|
||||
unsigned char erase_blk_en : 1;
|
||||
unsigned char c_size_mult_low : 1;
|
||||
// byte 11
|
||||
unsigned char wp_grp_size : 7;
|
||||
unsigned char sector_size_low : 1;
|
||||
// byte 12
|
||||
unsigned char write_bl_len_high : 2;
|
||||
unsigned char r2w_factor : 3;
|
||||
unsigned char reserved3 : 2;
|
||||
unsigned char wp_grp_enable : 1;
|
||||
// byte 13
|
||||
unsigned char reserved4 : 5;
|
||||
unsigned char write_partial : 1;
|
||||
unsigned char write_bl_len_low : 2;
|
||||
// byte 14
|
||||
unsigned char reserved5: 2;
|
||||
unsigned char file_format : 2;
|
||||
unsigned char tmp_write_protect : 1;
|
||||
unsigned char perm_write_protect : 1;
|
||||
unsigned char copy : 1;
|
||||
/** Indicates the file format on the card */
|
||||
unsigned char file_format_grp : 1;
|
||||
// byte 15
|
||||
unsigned char always1 : 1;
|
||||
unsigned char crc : 7;
|
||||
}csd1_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** CSD for version 2.00 cards */
|
||||
typedef struct CSDV2 {
|
||||
// byte 0
|
||||
unsigned char reserved1 : 6;
|
||||
unsigned char csd_ver : 2;
|
||||
// byte 1
|
||||
/** fixed to 0X0E */
|
||||
unsigned char taac;
|
||||
// byte 2
|
||||
/** fixed to 0 */
|
||||
unsigned char nsac;
|
||||
// byte 3
|
||||
unsigned char tran_speed;
|
||||
// byte 4
|
||||
unsigned char ccc_high;
|
||||
// byte 5
|
||||
/** This field is fixed to 9h, which indicates READ_BL_LEN=512 Byte */
|
||||
unsigned char read_bl_len : 4;
|
||||
unsigned char ccc_low : 4;
|
||||
// byte 6
|
||||
/** not used */
|
||||
unsigned char reserved2 : 4;
|
||||
unsigned char dsr_imp : 1;
|
||||
/** fixed to 0 */
|
||||
unsigned char read_blk_misalign :1;
|
||||
/** fixed to 0 */
|
||||
unsigned char write_blk_misalign : 1;
|
||||
/** fixed to 0 - no partial read */
|
||||
unsigned char read_bl_partial : 1;
|
||||
// byte 7
|
||||
/** not used */
|
||||
unsigned char reserved3 : 2;
|
||||
/** high part of card size */
|
||||
unsigned char c_size_high : 6;
|
||||
// byte 8
|
||||
/** middle part of card size */
|
||||
unsigned char c_size_mid;
|
||||
// byte 9
|
||||
/** low part of card size */
|
||||
unsigned char c_size_low;
|
||||
// byte 10
|
||||
/** sector size is fixed at 64 KB */
|
||||
unsigned char sector_size_high : 6;
|
||||
/** fixed to 1 - erase single is supported */
|
||||
unsigned char erase_blk_en : 1;
|
||||
/** not used */
|
||||
unsigned char reserved4 : 1;
|
||||
// byte 11
|
||||
unsigned char wp_grp_size : 7;
|
||||
/** sector size is fixed at 64 KB */
|
||||
unsigned char sector_size_low : 1;
|
||||
// byte 12
|
||||
/** write_bl_len fixed for 512 byte blocks */
|
||||
unsigned char write_bl_len_high : 2;
|
||||
/** fixed value of 2 */
|
||||
unsigned char r2w_factor : 3;
|
||||
/** not used */
|
||||
unsigned char reserved5 : 2;
|
||||
/** fixed value of 0 - no write protect groups */
|
||||
unsigned char wp_grp_enable : 1;
|
||||
// byte 13
|
||||
unsigned char reserved6 : 5;
|
||||
/** always zero - no partial block read*/
|
||||
unsigned char write_partial : 1;
|
||||
/** write_bl_len fixed for 512 byte blocks */
|
||||
unsigned char write_bl_len_low : 2;
|
||||
// byte 14
|
||||
unsigned char reserved7: 2;
|
||||
/** Do not use always 0 */
|
||||
unsigned char file_format : 2;
|
||||
unsigned char tmp_write_protect : 1;
|
||||
unsigned char perm_write_protect : 1;
|
||||
unsigned char copy : 1;
|
||||
/** Do not use always 0 */
|
||||
unsigned char file_format_grp : 1;
|
||||
// byte 15
|
||||
/** not used always 1 */
|
||||
unsigned char always1 : 1;
|
||||
/** checksum */
|
||||
unsigned char crc : 7;
|
||||
}csd2_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** union of old and new style CSD register */
|
||||
union csd_t {
|
||||
csd1_t v1;
|
||||
csd2_t v2;
|
||||
};
|
||||
#endif // SdInfo_h
|
||||
|
||||
#endif
|
|
@ -1,405 +1,405 @@
|
|||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#include "SdVolume.h"
|
||||
//------------------------------------------------------------------------------
|
||||
#if !USE_MULTIPLE_CARDS
|
||||
// raw block cache
|
||||
uint32_t SdVolume::cacheBlockNumber_; // current block number
|
||||
cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
|
||||
Sd2Card* SdVolume::sdCard_; // pointer to SD card object
|
||||
bool SdVolume::cacheDirty_; // cacheFlush() will write block if true
|
||||
uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT
|
||||
#endif // USE_MULTIPLE_CARDS
|
||||
//------------------------------------------------------------------------------
|
||||
// find a contiguous group of clusters
|
||||
bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
||||
// start of group
|
||||
uint32_t bgnCluster;
|
||||
// end of group
|
||||
uint32_t endCluster;
|
||||
// last cluster of FAT
|
||||
uint32_t fatEnd = clusterCount_ + 1;
|
||||
|
||||
// flag to save place to start next search
|
||||
bool setStart;
|
||||
|
||||
// set search start cluster
|
||||
if (*curCluster) {
|
||||
// try to make file contiguous
|
||||
bgnCluster = *curCluster + 1;
|
||||
|
||||
// don't save new start location
|
||||
setStart = false;
|
||||
} else {
|
||||
// start at likely place for free cluster
|
||||
bgnCluster = allocSearchStart_;
|
||||
|
||||
// save next search start if one cluster
|
||||
setStart = count == 1;
|
||||
}
|
||||
// end of group
|
||||
endCluster = bgnCluster;
|
||||
|
||||
// search the FAT for free clusters
|
||||
for (uint32_t n = 0;; n++, endCluster++) {
|
||||
// can't find space checked all clusters
|
||||
if (n >= clusterCount_) goto fail;
|
||||
|
||||
// past end - start from beginning of FAT
|
||||
if (endCluster > fatEnd) {
|
||||
bgnCluster = endCluster = 2;
|
||||
}
|
||||
uint32_t f;
|
||||
if (!fatGet(endCluster, &f)) goto fail;
|
||||
|
||||
if (f != 0) {
|
||||
// cluster in use try next cluster as bgnCluster
|
||||
bgnCluster = endCluster + 1;
|
||||
} else if ((endCluster - bgnCluster + 1) == count) {
|
||||
// done - found space
|
||||
break;
|
||||
}
|
||||
}
|
||||
// mark end of chain
|
||||
if (!fatPutEOC(endCluster)) goto fail;
|
||||
|
||||
// link clusters
|
||||
while (endCluster > bgnCluster) {
|
||||
if (!fatPut(endCluster - 1, endCluster)) goto fail;
|
||||
endCluster--;
|
||||
}
|
||||
if (*curCluster != 0) {
|
||||
// connect chains
|
||||
if (!fatPut(*curCluster, bgnCluster)) goto fail;
|
||||
}
|
||||
// return first cluster number to caller
|
||||
*curCluster = bgnCluster;
|
||||
|
||||
// remember possible next free cluster
|
||||
if (setStart) allocSearchStart_ = bgnCluster + 1;
|
||||
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdVolume::cacheFlush() {
|
||||
if (cacheDirty_) {
|
||||
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
|
||||
goto fail;
|
||||
}
|
||||
// mirror FAT tables
|
||||
if (cacheMirrorBlock_) {
|
||||
if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) {
|
||||
goto fail;
|
||||
}
|
||||
cacheMirrorBlock_ = 0;
|
||||
}
|
||||
cacheDirty_ = 0;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) {
|
||||
if (cacheBlockNumber_ != blockNumber) {
|
||||
if (!cacheFlush()) goto fail;
|
||||
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) goto fail;
|
||||
cacheBlockNumber_ = blockNumber;
|
||||
}
|
||||
if (dirty) cacheDirty_ = true;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// return the size in bytes of a cluster chain
|
||||
bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) {
|
||||
uint32_t s = 0;
|
||||
do {
|
||||
if (!fatGet(cluster, &cluster)) goto fail;
|
||||
s += 512UL << clusterSizeShift_;
|
||||
} while (!isEOC(cluster));
|
||||
*size = s;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Fetch a FAT entry
|
||||
bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
|
||||
uint32_t lba;
|
||||
if (cluster > (clusterCount_ + 1)) goto fail;
|
||||
if (FAT12_SUPPORT && fatType_ == 12) {
|
||||
uint16_t index = cluster;
|
||||
index += index >> 1;
|
||||
lba = fatStartBlock_ + (index >> 9);
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail;
|
||||
index &= 0X1FF;
|
||||
uint16_t tmp = cacheBuffer_.data[index];
|
||||
index++;
|
||||
if (index == 512) {
|
||||
if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) goto fail;
|
||||
index = 0;
|
||||
}
|
||||
tmp |= cacheBuffer_.data[index] << 8;
|
||||
*value = cluster & 1 ? tmp >> 4 : tmp & 0XFFF;
|
||||
return true;
|
||||
}
|
||||
if (fatType_ == 16) {
|
||||
lba = fatStartBlock_ + (cluster >> 8);
|
||||
} else if (fatType_ == 32) {
|
||||
lba = fatStartBlock_ + (cluster >> 7);
|
||||
} else {
|
||||
goto fail;
|
||||
}
|
||||
if (lba != cacheBlockNumber_) {
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail;
|
||||
}
|
||||
if (fatType_ == 16) {
|
||||
*value = cacheBuffer_.fat16[cluster & 0XFF];
|
||||
} else {
|
||||
*value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Store a FAT entry
|
||||
bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
|
||||
uint32_t lba;
|
||||
// error if reserved cluster
|
||||
if (cluster < 2) goto fail;
|
||||
|
||||
// error if not in FAT
|
||||
if (cluster > (clusterCount_ + 1)) goto fail;
|
||||
|
||||
if (FAT12_SUPPORT && fatType_ == 12) {
|
||||
uint16_t index = cluster;
|
||||
index += index >> 1;
|
||||
lba = fatStartBlock_ + (index >> 9);
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
|
||||
// mirror second FAT
|
||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||
index &= 0X1FF;
|
||||
uint8_t tmp = value;
|
||||
if (cluster & 1) {
|
||||
tmp = (cacheBuffer_.data[index] & 0XF) | tmp << 4;
|
||||
}
|
||||
cacheBuffer_.data[index] = tmp;
|
||||
index++;
|
||||
if (index == 512) {
|
||||
lba++;
|
||||
index = 0;
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
|
||||
// mirror second FAT
|
||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||
}
|
||||
tmp = value >> 4;
|
||||
if (!(cluster & 1)) {
|
||||
tmp = ((cacheBuffer_.data[index] & 0XF0)) | tmp >> 4;
|
||||
}
|
||||
cacheBuffer_.data[index] = tmp;
|
||||
return true;
|
||||
}
|
||||
if (fatType_ == 16) {
|
||||
lba = fatStartBlock_ + (cluster >> 8);
|
||||
} else if (fatType_ == 32) {
|
||||
lba = fatStartBlock_ + (cluster >> 7);
|
||||
} else {
|
||||
goto fail;
|
||||
}
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
|
||||
// store entry
|
||||
if (fatType_ == 16) {
|
||||
cacheBuffer_.fat16[cluster & 0XFF] = value;
|
||||
} else {
|
||||
cacheBuffer_.fat32[cluster & 0X7F] = value;
|
||||
}
|
||||
// mirror second FAT
|
||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// free a cluster chain
|
||||
bool SdVolume::freeChain(uint32_t cluster) {
|
||||
uint32_t next;
|
||||
|
||||
// clear free cluster location
|
||||
allocSearchStart_ = 2;
|
||||
|
||||
do {
|
||||
if (!fatGet(cluster, &next)) goto fail;
|
||||
|
||||
// free cluster
|
||||
if (!fatPut(cluster, 0)) goto fail;
|
||||
|
||||
cluster = next;
|
||||
} while (!isEOC(cluster));
|
||||
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Volume free space in clusters.
|
||||
*
|
||||
* \return Count of free clusters for success or -1 if an error occurs.
|
||||
*/
|
||||
int32_t SdVolume::freeClusterCount() {
|
||||
uint32_t free = 0;
|
||||
uint16_t n;
|
||||
uint32_t todo = clusterCount_ + 2;
|
||||
|
||||
if (fatType_ == 16) {
|
||||
n = 256;
|
||||
} else if (fatType_ == 32) {
|
||||
n = 128;
|
||||
} else {
|
||||
// put FAT12 here
|
||||
return -1;
|
||||
}
|
||||
|
||||
for (uint32_t lba = fatStartBlock_; todo; todo -= n, lba++) {
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) return -1;
|
||||
if (todo < n) n = todo;
|
||||
if (fatType_ == 16) {
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
if (cacheBuffer_.fat16[i] == 0) free++;
|
||||
}
|
||||
} else {
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
if (cacheBuffer_.fat32[i] == 0) free++;
|
||||
}
|
||||
}
|
||||
}
|
||||
return free;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Initialize a FAT volume.
|
||||
*
|
||||
* \param[in] dev The SD card where the volume is located.
|
||||
*
|
||||
* \param[in] part The partition to be used. Legal values for \a part are
|
||||
* 1-4 to use the corresponding partition on a device formatted with
|
||||
* a MBR, Master Boot Record, or zero if the device is formatted as
|
||||
* a super floppy with the FAT boot sector in block zero.
|
||||
*
|
||||
* \return The value one, true, is returned for success and
|
||||
* the value zero, false, is returned for failure. Reasons for
|
||||
* failure include not finding a valid partition, not finding a valid
|
||||
* FAT file system in the specified partition or an I/O error.
|
||||
*/
|
||||
bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
||||
uint32_t totalBlocks;
|
||||
uint32_t volumeStartBlock = 0;
|
||||
fat32_boot_t* fbs;
|
||||
|
||||
sdCard_ = dev;
|
||||
fatType_ = 0;
|
||||
allocSearchStart_ = 2;
|
||||
cacheDirty_ = 0; // cacheFlush() will write block if true
|
||||
cacheMirrorBlock_ = 0;
|
||||
cacheBlockNumber_ = 0XFFFFFFFF;
|
||||
|
||||
// if part == 0 assume super floppy with FAT boot sector in block zero
|
||||
// if part > 0 assume mbr volume with partition table
|
||||
if (part) {
|
||||
if (part > 4)goto fail;
|
||||
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
|
||||
part_t* p = &cacheBuffer_.mbr.part[part-1];
|
||||
if ((p->boot & 0X7F) !=0 ||
|
||||
p->totalSectors < 100 ||
|
||||
p->firstSector == 0) {
|
||||
// not a valid partition
|
||||
goto fail;
|
||||
}
|
||||
volumeStartBlock = p->firstSector;
|
||||
}
|
||||
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
|
||||
fbs = &cacheBuffer_.fbs32;
|
||||
if (fbs->bytesPerSector != 512 ||
|
||||
fbs->fatCount == 0 ||
|
||||
fbs->reservedSectorCount == 0 ||
|
||||
fbs->sectorsPerCluster == 0) {
|
||||
// not valid FAT volume
|
||||
goto fail;
|
||||
}
|
||||
fatCount_ = fbs->fatCount;
|
||||
blocksPerCluster_ = fbs->sectorsPerCluster;
|
||||
// determine shift that is same as multiply by blocksPerCluster_
|
||||
clusterSizeShift_ = 0;
|
||||
while (blocksPerCluster_ != (1 << clusterSizeShift_)) {
|
||||
// error if not power of 2
|
||||
if (clusterSizeShift_++ > 7) goto fail;
|
||||
}
|
||||
blocksPerFat_ = fbs->sectorsPerFat16 ?
|
||||
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
|
||||
|
||||
fatStartBlock_ = volumeStartBlock + fbs->reservedSectorCount;
|
||||
|
||||
// count for FAT16 zero for FAT32
|
||||
rootDirEntryCount_ = fbs->rootDirEntryCount;
|
||||
|
||||
// directory start for FAT16 dataStart for FAT32
|
||||
rootDirStart_ = fatStartBlock_ + fbs->fatCount * blocksPerFat_;
|
||||
|
||||
// data start for FAT16 and FAT32
|
||||
dataStartBlock_ = rootDirStart_ + ((32 * fbs->rootDirEntryCount + 511)/512);
|
||||
|
||||
// total blocks for FAT16 or FAT32
|
||||
totalBlocks = fbs->totalSectors16 ?
|
||||
fbs->totalSectors16 : fbs->totalSectors32;
|
||||
// total data blocks
|
||||
clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock);
|
||||
|
||||
// divide by cluster size to get cluster count
|
||||
clusterCount_ >>= clusterSizeShift_;
|
||||
|
||||
// FAT type is determined by cluster count
|
||||
if (clusterCount_ < 4085) {
|
||||
fatType_ = 12;
|
||||
if (!FAT12_SUPPORT) goto fail;
|
||||
} else if (clusterCount_ < 65525) {
|
||||
fatType_ = 16;
|
||||
} else {
|
||||
rootDirStart_ = fbs->fat32RootCluster;
|
||||
fatType_ = 32;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "Marlin.h"
|
||||
#ifdef SDSUPPORT
|
||||
|
||||
#include "SdVolume.h"
|
||||
//------------------------------------------------------------------------------
|
||||
#if !USE_MULTIPLE_CARDS
|
||||
// raw block cache
|
||||
uint32_t SdVolume::cacheBlockNumber_; // current block number
|
||||
cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
|
||||
Sd2Card* SdVolume::sdCard_; // pointer to SD card object
|
||||
bool SdVolume::cacheDirty_; // cacheFlush() will write block if true
|
||||
uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT
|
||||
#endif // USE_MULTIPLE_CARDS
|
||||
//------------------------------------------------------------------------------
|
||||
// find a contiguous group of clusters
|
||||
bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
||||
// start of group
|
||||
uint32_t bgnCluster;
|
||||
// end of group
|
||||
uint32_t endCluster;
|
||||
// last cluster of FAT
|
||||
uint32_t fatEnd = clusterCount_ + 1;
|
||||
|
||||
// flag to save place to start next search
|
||||
bool setStart;
|
||||
|
||||
// set search start cluster
|
||||
if (*curCluster) {
|
||||
// try to make file contiguous
|
||||
bgnCluster = *curCluster + 1;
|
||||
|
||||
// don't save new start location
|
||||
setStart = false;
|
||||
} else {
|
||||
// start at likely place for free cluster
|
||||
bgnCluster = allocSearchStart_;
|
||||
|
||||
// save next search start if one cluster
|
||||
setStart = count == 1;
|
||||
}
|
||||
// end of group
|
||||
endCluster = bgnCluster;
|
||||
|
||||
// search the FAT for free clusters
|
||||
for (uint32_t n = 0;; n++, endCluster++) {
|
||||
// can't find space checked all clusters
|
||||
if (n >= clusterCount_) goto fail;
|
||||
|
||||
// past end - start from beginning of FAT
|
||||
if (endCluster > fatEnd) {
|
||||
bgnCluster = endCluster = 2;
|
||||
}
|
||||
uint32_t f;
|
||||
if (!fatGet(endCluster, &f)) goto fail;
|
||||
|
||||
if (f != 0) {
|
||||
// cluster in use try next cluster as bgnCluster
|
||||
bgnCluster = endCluster + 1;
|
||||
} else if ((endCluster - bgnCluster + 1) == count) {
|
||||
// done - found space
|
||||
break;
|
||||
}
|
||||
}
|
||||
// mark end of chain
|
||||
if (!fatPutEOC(endCluster)) goto fail;
|
||||
|
||||
// link clusters
|
||||
while (endCluster > bgnCluster) {
|
||||
if (!fatPut(endCluster - 1, endCluster)) goto fail;
|
||||
endCluster--;
|
||||
}
|
||||
if (*curCluster != 0) {
|
||||
// connect chains
|
||||
if (!fatPut(*curCluster, bgnCluster)) goto fail;
|
||||
}
|
||||
// return first cluster number to caller
|
||||
*curCluster = bgnCluster;
|
||||
|
||||
// remember possible next free cluster
|
||||
if (setStart) allocSearchStart_ = bgnCluster + 1;
|
||||
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdVolume::cacheFlush() {
|
||||
if (cacheDirty_) {
|
||||
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
|
||||
goto fail;
|
||||
}
|
||||
// mirror FAT tables
|
||||
if (cacheMirrorBlock_) {
|
||||
if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) {
|
||||
goto fail;
|
||||
}
|
||||
cacheMirrorBlock_ = 0;
|
||||
}
|
||||
cacheDirty_ = 0;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) {
|
||||
if (cacheBlockNumber_ != blockNumber) {
|
||||
if (!cacheFlush()) goto fail;
|
||||
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) goto fail;
|
||||
cacheBlockNumber_ = blockNumber;
|
||||
}
|
||||
if (dirty) cacheDirty_ = true;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// return the size in bytes of a cluster chain
|
||||
bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) {
|
||||
uint32_t s = 0;
|
||||
do {
|
||||
if (!fatGet(cluster, &cluster)) goto fail;
|
||||
s += 512UL << clusterSizeShift_;
|
||||
} while (!isEOC(cluster));
|
||||
*size = s;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Fetch a FAT entry
|
||||
bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
|
||||
uint32_t lba;
|
||||
if (cluster > (clusterCount_ + 1)) goto fail;
|
||||
if (FAT12_SUPPORT && fatType_ == 12) {
|
||||
uint16_t index = cluster;
|
||||
index += index >> 1;
|
||||
lba = fatStartBlock_ + (index >> 9);
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail;
|
||||
index &= 0X1FF;
|
||||
uint16_t tmp = cacheBuffer_.data[index];
|
||||
index++;
|
||||
if (index == 512) {
|
||||
if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) goto fail;
|
||||
index = 0;
|
||||
}
|
||||
tmp |= cacheBuffer_.data[index] << 8;
|
||||
*value = cluster & 1 ? tmp >> 4 : tmp & 0XFFF;
|
||||
return true;
|
||||
}
|
||||
if (fatType_ == 16) {
|
||||
lba = fatStartBlock_ + (cluster >> 8);
|
||||
} else if (fatType_ == 32) {
|
||||
lba = fatStartBlock_ + (cluster >> 7);
|
||||
} else {
|
||||
goto fail;
|
||||
}
|
||||
if (lba != cacheBlockNumber_) {
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail;
|
||||
}
|
||||
if (fatType_ == 16) {
|
||||
*value = cacheBuffer_.fat16[cluster & 0XFF];
|
||||
} else {
|
||||
*value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Store a FAT entry
|
||||
bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
|
||||
uint32_t lba;
|
||||
// error if reserved cluster
|
||||
if (cluster < 2) goto fail;
|
||||
|
||||
// error if not in FAT
|
||||
if (cluster > (clusterCount_ + 1)) goto fail;
|
||||
|
||||
if (FAT12_SUPPORT && fatType_ == 12) {
|
||||
uint16_t index = cluster;
|
||||
index += index >> 1;
|
||||
lba = fatStartBlock_ + (index >> 9);
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
|
||||
// mirror second FAT
|
||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||
index &= 0X1FF;
|
||||
uint8_t tmp = value;
|
||||
if (cluster & 1) {
|
||||
tmp = (cacheBuffer_.data[index] & 0XF) | tmp << 4;
|
||||
}
|
||||
cacheBuffer_.data[index] = tmp;
|
||||
index++;
|
||||
if (index == 512) {
|
||||
lba++;
|
||||
index = 0;
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
|
||||
// mirror second FAT
|
||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||
}
|
||||
tmp = value >> 4;
|
||||
if (!(cluster & 1)) {
|
||||
tmp = ((cacheBuffer_.data[index] & 0XF0)) | tmp >> 4;
|
||||
}
|
||||
cacheBuffer_.data[index] = tmp;
|
||||
return true;
|
||||
}
|
||||
if (fatType_ == 16) {
|
||||
lba = fatStartBlock_ + (cluster >> 8);
|
||||
} else if (fatType_ == 32) {
|
||||
lba = fatStartBlock_ + (cluster >> 7);
|
||||
} else {
|
||||
goto fail;
|
||||
}
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
|
||||
// store entry
|
||||
if (fatType_ == 16) {
|
||||
cacheBuffer_.fat16[cluster & 0XFF] = value;
|
||||
} else {
|
||||
cacheBuffer_.fat32[cluster & 0X7F] = value;
|
||||
}
|
||||
// mirror second FAT
|
||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// free a cluster chain
|
||||
bool SdVolume::freeChain(uint32_t cluster) {
|
||||
uint32_t next;
|
||||
|
||||
// clear free cluster location
|
||||
allocSearchStart_ = 2;
|
||||
|
||||
do {
|
||||
if (!fatGet(cluster, &next)) goto fail;
|
||||
|
||||
// free cluster
|
||||
if (!fatPut(cluster, 0)) goto fail;
|
||||
|
||||
cluster = next;
|
||||
} while (!isEOC(cluster));
|
||||
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Volume free space in clusters.
|
||||
*
|
||||
* \return Count of free clusters for success or -1 if an error occurs.
|
||||
*/
|
||||
int32_t SdVolume::freeClusterCount() {
|
||||
uint32_t free = 0;
|
||||
uint16_t n;
|
||||
uint32_t todo = clusterCount_ + 2;
|
||||
|
||||
if (fatType_ == 16) {
|
||||
n = 256;
|
||||
} else if (fatType_ == 32) {
|
||||
n = 128;
|
||||
} else {
|
||||
// put FAT12 here
|
||||
return -1;
|
||||
}
|
||||
|
||||
for (uint32_t lba = fatStartBlock_; todo; todo -= n, lba++) {
|
||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) return -1;
|
||||
if (todo < n) n = todo;
|
||||
if (fatType_ == 16) {
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
if (cacheBuffer_.fat16[i] == 0) free++;
|
||||
}
|
||||
} else {
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
if (cacheBuffer_.fat32[i] == 0) free++;
|
||||
}
|
||||
}
|
||||
}
|
||||
return free;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Initialize a FAT volume.
|
||||
*
|
||||
* \param[in] dev The SD card where the volume is located.
|
||||
*
|
||||
* \param[in] part The partition to be used. Legal values for \a part are
|
||||
* 1-4 to use the corresponding partition on a device formatted with
|
||||
* a MBR, Master Boot Record, or zero if the device is formatted as
|
||||
* a super floppy with the FAT boot sector in block zero.
|
||||
*
|
||||
* \return The value one, true, is returned for success and
|
||||
* the value zero, false, is returned for failure. Reasons for
|
||||
* failure include not finding a valid partition, not finding a valid
|
||||
* FAT file system in the specified partition or an I/O error.
|
||||
*/
|
||||
bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
||||
uint32_t totalBlocks;
|
||||
uint32_t volumeStartBlock = 0;
|
||||
fat32_boot_t* fbs;
|
||||
|
||||
sdCard_ = dev;
|
||||
fatType_ = 0;
|
||||
allocSearchStart_ = 2;
|
||||
cacheDirty_ = 0; // cacheFlush() will write block if true
|
||||
cacheMirrorBlock_ = 0;
|
||||
cacheBlockNumber_ = 0XFFFFFFFF;
|
||||
|
||||
// if part == 0 assume super floppy with FAT boot sector in block zero
|
||||
// if part > 0 assume mbr volume with partition table
|
||||
if (part) {
|
||||
if (part > 4)goto fail;
|
||||
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
|
||||
part_t* p = &cacheBuffer_.mbr.part[part-1];
|
||||
if ((p->boot & 0X7F) !=0 ||
|
||||
p->totalSectors < 100 ||
|
||||
p->firstSector == 0) {
|
||||
// not a valid partition
|
||||
goto fail;
|
||||
}
|
||||
volumeStartBlock = p->firstSector;
|
||||
}
|
||||
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
|
||||
fbs = &cacheBuffer_.fbs32;
|
||||
if (fbs->bytesPerSector != 512 ||
|
||||
fbs->fatCount == 0 ||
|
||||
fbs->reservedSectorCount == 0 ||
|
||||
fbs->sectorsPerCluster == 0) {
|
||||
// not valid FAT volume
|
||||
goto fail;
|
||||
}
|
||||
fatCount_ = fbs->fatCount;
|
||||
blocksPerCluster_ = fbs->sectorsPerCluster;
|
||||
// determine shift that is same as multiply by blocksPerCluster_
|
||||
clusterSizeShift_ = 0;
|
||||
while (blocksPerCluster_ != (1 << clusterSizeShift_)) {
|
||||
// error if not power of 2
|
||||
if (clusterSizeShift_++ > 7) goto fail;
|
||||
}
|
||||
blocksPerFat_ = fbs->sectorsPerFat16 ?
|
||||
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
|
||||
|
||||
fatStartBlock_ = volumeStartBlock + fbs->reservedSectorCount;
|
||||
|
||||
// count for FAT16 zero for FAT32
|
||||
rootDirEntryCount_ = fbs->rootDirEntryCount;
|
||||
|
||||
// directory start for FAT16 dataStart for FAT32
|
||||
rootDirStart_ = fatStartBlock_ + fbs->fatCount * blocksPerFat_;
|
||||
|
||||
// data start for FAT16 and FAT32
|
||||
dataStartBlock_ = rootDirStart_ + ((32 * fbs->rootDirEntryCount + 511)/512);
|
||||
|
||||
// total blocks for FAT16 or FAT32
|
||||
totalBlocks = fbs->totalSectors16 ?
|
||||
fbs->totalSectors16 : fbs->totalSectors32;
|
||||
// total data blocks
|
||||
clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock);
|
||||
|
||||
// divide by cluster size to get cluster count
|
||||
clusterCount_ >>= clusterSizeShift_;
|
||||
|
||||
// FAT type is determined by cluster count
|
||||
if (clusterCount_ < 4085) {
|
||||
fatType_ = 12;
|
||||
if (!FAT12_SUPPORT) goto fail;
|
||||
} else if (clusterCount_ < 65525) {
|
||||
fatType_ = 16;
|
||||
} else {
|
||||
rootDirStart_ = fbs->fat32RootCluster;
|
||||
fatType_ = 32;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
#endif
|
|
@ -3,13 +3,14 @@
|
|||
|
||||
#define BOARD_UNKNOWN -1
|
||||
|
||||
#define BOARD_RAMBO 100 // Rambo - 100 (orig 301)
|
||||
|
||||
#define BOARD_RAMBO 301 // Rambo
|
||||
#define BOARD_RAMBO_MINI_1_3 302 // Rambo-mini 1.3
|
||||
#define BOARD_RAMBO_MINI_1_0 102 // Rambo-mini 1.0
|
||||
#define BOARD_RAMBO_MINI_1_0 200 // Rambo-mini 1.0 - 200 (orig 102)
|
||||
#define BOARD_RAMBO_MINI_1_3 203 // Rambo-mini 1.3 - 203 (orig 302)
|
||||
|
||||
|
||||
#define BOARD_99 99 // This is in pins.h but...?
|
||||
#define BOARD_EISNY_0_3a 303 // EINY 0.3a - 303 (orig 300)
|
||||
#define BOARD_EINSY_0_4a 304 // EINY 0.4a - 304 (orig 299)
|
||||
#define BOARD_EINSY_0_5a 305 // EINY 0.5a - 305 (orig 298)
|
||||
|
||||
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
||||
#define IS_RAMPS (MB(RAMPS_OLD) || MB(RAMPS_13_EFB) || MB(RAMPS_13_EEB) || MB(RAMPS_13_EFF) || MB(RAMPS_13_EEF))
|
||||
|
|
|
@ -81,7 +81,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
|||
if(lsAction==LS_SerialPrint)
|
||||
{
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLN(MSG_SD_CANT_OPEN_SUBDIR);
|
||||
SERIAL_ECHORPGM(MSG_SD_CANT_ENTER_SUBDIR);
|
||||
SERIAL_ECHOLN(lfilename);
|
||||
}
|
||||
}
|
||||
|
@ -233,6 +233,15 @@ void CardReader::openLogFile(char* name)
|
|||
openFile(name, false);
|
||||
}
|
||||
|
||||
void CardReader::getDirName(char* name, uint8_t level)
|
||||
{
|
||||
workDirParents[level].getFilename(name);
|
||||
}
|
||||
|
||||
uint16_t CardReader::getWorkDirDepth() {
|
||||
return workDirDepth;
|
||||
}
|
||||
|
||||
void CardReader::getAbsFilename(char *t)
|
||||
{
|
||||
uint8_t cnt=0;
|
||||
|
@ -262,7 +271,7 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
|
|||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
|
||||
SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
|
||||
kill();
|
||||
kill("", 1);
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -501,6 +510,19 @@ void CardReader::write_command(char *buf)
|
|||
}
|
||||
}
|
||||
|
||||
#define CHUNK_SIZE 64
|
||||
|
||||
void CardReader::write_command_no_newline(char *buf)
|
||||
{
|
||||
file.write(buf, CHUNK_SIZE);
|
||||
if (file.writeError)
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_SD_ERR_WRITE_TO_FILE);
|
||||
MYSERIAL.println("An error while writing to the SD Card.");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void CardReader::checkautostart(bool force)
|
||||
{
|
||||
|
@ -622,7 +644,7 @@ void CardReader::updir()
|
|||
{
|
||||
--workDirDepth;
|
||||
workDir = workDirParents[0];
|
||||
int d;
|
||||
int d;
|
||||
for (int d = 0; d < workDirDepth; d++)
|
||||
workDirParents[d] = workDirParents[d+1];
|
||||
}
|
||||
|
|
|
@ -14,6 +14,7 @@ public:
|
|||
|
||||
void initsd();
|
||||
void write_command(char *buf);
|
||||
void write_command_no_newline(char *buf);
|
||||
//files auto[0-9].g on the sd card are performed in a row
|
||||
//this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
|
||||
|
||||
|
@ -32,6 +33,8 @@ public:
|
|||
uint16_t getnrfilenames();
|
||||
|
||||
void getAbsFilename(char *t);
|
||||
void getDirName(char* name, uint8_t level);
|
||||
uint16_t getWorkDirDepth();
|
||||
|
||||
|
||||
void ls();
|
||||
|
@ -46,7 +49,10 @@ public:
|
|||
FORCE_INLINE void setIndex(long index) {sdpos = index;file.seekSet(index);};
|
||||
FORCE_INLINE uint8_t percentDone(){if(!isFileOpen()) return 0; if(filesize) return sdpos/((filesize+99)/100); else return 0;};
|
||||
FORCE_INLINE char* getWorkDirName(){workDir.getFilename(filename);return filename;};
|
||||
FORCE_INLINE uint32_t get_sdpos() { if (!isFileOpen()) return 0; else return(sdpos); };
|
||||
|
||||
bool ToshibaFlashAir_isEnabled() const { return card.getFlashAirCompatible(); }
|
||||
void ToshibaFlashAir_enable(bool enable) { card.setFlashAirCompatible(enable); }
|
||||
bool ToshibaFlashAir_GetIP(uint8_t *ip);
|
||||
|
||||
public:
|
||||
|
|
680
Firmware/cmdqueue.cpp
Normal file
680
Firmware/cmdqueue.cpp
Normal file
|
@ -0,0 +1,680 @@
|
|||
#include "cmdqueue.h"
|
||||
#include "cardreader.h"
|
||||
#include "ultralcd.h"
|
||||
|
||||
extern bool Stopped;
|
||||
|
||||
// Reserve BUFSIZE lines of length MAX_CMD_SIZE plus CMDBUFFER_RESERVE_FRONT.
|
||||
char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
|
||||
// Head of the circular buffer, where to read.
|
||||
int bufindr = 0;
|
||||
// Tail of the buffer, where to write.
|
||||
int bufindw = 0;
|
||||
// Number of lines in cmdbuffer.
|
||||
int buflen = 0;
|
||||
// Flag for processing the current command inside the main Arduino loop().
|
||||
// If a new command was pushed to the front of a command buffer while
|
||||
// processing another command, this replaces the command on the top.
|
||||
// Therefore don't remove the command from the queue in the loop() function.
|
||||
bool cmdbuffer_front_already_processed = false;
|
||||
|
||||
int serial_count = 0; //index of character read from serial line
|
||||
boolean comment_mode = false;
|
||||
char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
|
||||
|
||||
unsigned long TimeSent = millis();
|
||||
unsigned long TimeNow = millis();
|
||||
|
||||
long gcode_N = 0;
|
||||
long gcode_LastN = 0;
|
||||
long Stopped_gcode_LastN = 0;
|
||||
|
||||
uint32_t sdpos_atomic = 0;
|
||||
|
||||
|
||||
// Pop the currently processed command from the queue.
|
||||
// It is expected, that there is at least one command in the queue.
|
||||
bool cmdqueue_pop_front()
|
||||
{
|
||||
if (buflen > 0) {
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
SERIAL_ECHOPGM("Dequeing ");
|
||||
SERIAL_ECHO(cmdbuffer+bufindr+CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
SERIAL_ECHOPGM("Old indices: buflen ");
|
||||
SERIAL_ECHO(buflen);
|
||||
SERIAL_ECHOPGM(", bufindr ");
|
||||
SERIAL_ECHO(bufindr);
|
||||
SERIAL_ECHOPGM(", bufindw ");
|
||||
SERIAL_ECHO(bufindw);
|
||||
SERIAL_ECHOPGM(", serial_count ");
|
||||
SERIAL_ECHO(serial_count);
|
||||
SERIAL_ECHOPGM(", bufsize ");
|
||||
SERIAL_ECHO(sizeof(cmdbuffer));
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
if (-- buflen == 0) {
|
||||
// Empty buffer.
|
||||
if (serial_count == 0)
|
||||
// No serial communication is pending. Reset both pointers to zero.
|
||||
bufindw = 0;
|
||||
bufindr = bufindw;
|
||||
} else {
|
||||
// There is at least one ready line in the buffer.
|
||||
// First skip the current command ID and iterate up to the end of the string.
|
||||
for (bufindr += CMDHDRSIZE; cmdbuffer[bufindr] != 0; ++ bufindr) ;
|
||||
// Second, skip the end of string null character and iterate until a nonzero command ID is found.
|
||||
for (++ bufindr; bufindr < sizeof(cmdbuffer) && cmdbuffer[bufindr] == 0; ++ bufindr) ;
|
||||
// If the end of the buffer was empty,
|
||||
if (bufindr == sizeof(cmdbuffer)) {
|
||||
// skip to the start and find the nonzero command.
|
||||
for (bufindr = 0; cmdbuffer[bufindr] == 0; ++ bufindr) ;
|
||||
}
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
SERIAL_ECHOPGM("New indices: buflen ");
|
||||
SERIAL_ECHO(buflen);
|
||||
SERIAL_ECHOPGM(", bufindr ");
|
||||
SERIAL_ECHO(bufindr);
|
||||
SERIAL_ECHOPGM(", bufindw ");
|
||||
SERIAL_ECHO(bufindw);
|
||||
SERIAL_ECHOPGM(", serial_count ");
|
||||
SERIAL_ECHO(serial_count);
|
||||
SERIAL_ECHOPGM(" new command on the top: ");
|
||||
SERIAL_ECHO(cmdbuffer+bufindr+CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void cmdqueue_reset()
|
||||
{
|
||||
bufindr = 0;
|
||||
bufindw = 0;
|
||||
buflen = 0;
|
||||
cmdbuffer_front_already_processed = false;
|
||||
}
|
||||
|
||||
// How long a string could be pushed to the front of the command queue?
|
||||
// If yes, adjust bufindr to the new position, where the new command could be enqued.
|
||||
// len_asked does not contain the zero terminator size.
|
||||
bool cmdqueue_could_enqueue_front(int len_asked)
|
||||
{
|
||||
// MAX_CMD_SIZE has to accommodate the zero terminator.
|
||||
if (len_asked >= MAX_CMD_SIZE)
|
||||
return false;
|
||||
// Remove the currently processed command from the queue.
|
||||
if (! cmdbuffer_front_already_processed) {
|
||||
cmdqueue_pop_front();
|
||||
cmdbuffer_front_already_processed = true;
|
||||
}
|
||||
if (bufindr == bufindw && buflen > 0)
|
||||
// Full buffer.
|
||||
return false;
|
||||
// Adjust the end of the write buffer based on whether a partial line is in the receive buffer.
|
||||
int endw = (serial_count > 0) ? (bufindw + MAX_CMD_SIZE + 1) : bufindw;
|
||||
if (bufindw < bufindr) {
|
||||
int bufindr_new = bufindr - len_asked - (1 + CMDHDRSIZE);
|
||||
// Simple case. There is a contiguous space between the write buffer and the read buffer.
|
||||
if (endw <= bufindr_new) {
|
||||
bufindr = bufindr_new;
|
||||
return true;
|
||||
}
|
||||
} else {
|
||||
// Otherwise the free space is split between the start and end.
|
||||
if (len_asked + (1 + CMDHDRSIZE) <= bufindr) {
|
||||
// Could fit at the start.
|
||||
bufindr -= len_asked + (1 + CMDHDRSIZE);
|
||||
return true;
|
||||
}
|
||||
int bufindr_new = sizeof(cmdbuffer) - len_asked - (1 + CMDHDRSIZE);
|
||||
if (endw <= bufindr_new) {
|
||||
memset(cmdbuffer, 0, bufindr);
|
||||
bufindr = bufindr_new;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// Could one enqueue a command of length len_asked into the buffer,
|
||||
// while leaving CMDBUFFER_RESERVE_FRONT at the start?
|
||||
// If yes, adjust bufindw to the new position, where the new command could be enqued.
|
||||
// len_asked does not contain the zero terminator size.
|
||||
// This function may update bufindw, therefore for the power panic to work, this function must be called
|
||||
// with the interrupts disabled!
|
||||
bool cmdqueue_could_enqueue_back(int len_asked, bool atomic_update)
|
||||
{
|
||||
// MAX_CMD_SIZE has to accommodate the zero terminator.
|
||||
if (len_asked >= MAX_CMD_SIZE)
|
||||
return false;
|
||||
|
||||
if (bufindr == bufindw && buflen > 0)
|
||||
// Full buffer.
|
||||
return false;
|
||||
|
||||
if (serial_count > 0) {
|
||||
// If there is some data stored starting at bufindw, len_asked is certainly smaller than
|
||||
// the allocated data buffer. Try to reserve a new buffer and to move the already received
|
||||
// serial data.
|
||||
// How much memory to reserve for the commands pushed to the front?
|
||||
// End of the queue, when pushing to the end.
|
||||
int endw = bufindw + len_asked + (1 + CMDHDRSIZE);
|
||||
if (bufindw < bufindr)
|
||||
// Simple case. There is a contiguous space between the write buffer and the read buffer.
|
||||
return endw + CMDBUFFER_RESERVE_FRONT <= bufindr;
|
||||
// Otherwise the free space is split between the start and end.
|
||||
if (// Could one fit to the end, including the reserve?
|
||||
endw + CMDBUFFER_RESERVE_FRONT <= sizeof(cmdbuffer) ||
|
||||
// Could one fit to the end, and the reserve to the start?
|
||||
(endw <= sizeof(cmdbuffer) && CMDBUFFER_RESERVE_FRONT <= bufindr))
|
||||
return true;
|
||||
// Could one fit both to the start?
|
||||
if (len_asked + (1 + CMDHDRSIZE) + CMDBUFFER_RESERVE_FRONT <= bufindr) {
|
||||
// Mark the rest of the buffer as used.
|
||||
memset(cmdbuffer+bufindw, 0, sizeof(cmdbuffer)-bufindw);
|
||||
// and point to the start.
|
||||
// Be careful! The bufindw needs to be changed atomically for the power panic & filament panic to work.
|
||||
if (atomic_update)
|
||||
cli();
|
||||
bufindw = 0;
|
||||
if (atomic_update)
|
||||
sei();
|
||||
return true;
|
||||
}
|
||||
} else {
|
||||
// How much memory to reserve for the commands pushed to the front?
|
||||
// End of the queue, when pushing to the end.
|
||||
int endw = bufindw + len_asked + (1 + CMDHDRSIZE);
|
||||
if (bufindw < bufindr)
|
||||
// Simple case. There is a contiguous space between the write buffer and the read buffer.
|
||||
return endw + CMDBUFFER_RESERVE_FRONT <= bufindr;
|
||||
// Otherwise the free space is split between the start and end.
|
||||
if (// Could one fit to the end, including the reserve?
|
||||
endw + CMDBUFFER_RESERVE_FRONT <= sizeof(cmdbuffer) ||
|
||||
// Could one fit to the end, and the reserve to the start?
|
||||
(endw <= sizeof(cmdbuffer) && CMDBUFFER_RESERVE_FRONT <= bufindr))
|
||||
return true;
|
||||
// Could one fit both to the start?
|
||||
if (len_asked + (1 + CMDHDRSIZE) + CMDBUFFER_RESERVE_FRONT <= bufindr) {
|
||||
// Mark the rest of the buffer as used.
|
||||
memset(cmdbuffer+bufindw, 0, sizeof(cmdbuffer)-bufindw);
|
||||
// and point to the start.
|
||||
// Be careful! The bufindw needs to be changed atomically for the power panic & filament panic to work.
|
||||
if (atomic_update)
|
||||
cli();
|
||||
bufindw = 0;
|
||||
if (atomic_update)
|
||||
sei();
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
void cmdqueue_dump_to_serial_single_line(int nr, const char *p)
|
||||
{
|
||||
SERIAL_ECHOPGM("Entry nr: ");
|
||||
SERIAL_ECHO(nr);
|
||||
SERIAL_ECHOPGM(", type: ");
|
||||
SERIAL_ECHO(int(*p));
|
||||
SERIAL_ECHOPGM(", cmd: ");
|
||||
SERIAL_ECHO(p+1);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
}
|
||||
|
||||
void cmdqueue_dump_to_serial()
|
||||
{
|
||||
if (buflen == 0) {
|
||||
SERIAL_ECHOLNPGM("The command buffer is empty.");
|
||||
} else {
|
||||
SERIAL_ECHOPGM("Content of the buffer: entries ");
|
||||
SERIAL_ECHO(buflen);
|
||||
SERIAL_ECHOPGM(", indr ");
|
||||
SERIAL_ECHO(bufindr);
|
||||
SERIAL_ECHOPGM(", indw ");
|
||||
SERIAL_ECHO(bufindw);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
int nr = 0;
|
||||
if (bufindr < bufindw) {
|
||||
for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + bufindw; ++ nr) {
|
||||
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||
// Skip the command.
|
||||
for (++p; *p != 0; ++ p);
|
||||
// Skip the gaps.
|
||||
for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
|
||||
}
|
||||
} else {
|
||||
for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + sizeof(cmdbuffer); ++ nr) {
|
||||
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||
// Skip the command.
|
||||
for (++p; *p != 0; ++ p);
|
||||
// Skip the gaps.
|
||||
for (++p; p < cmdbuffer + sizeof(cmdbuffer) && *p == 0; ++ p);
|
||||
}
|
||||
for (const char *p = cmdbuffer; p < cmdbuffer + bufindw; ++ nr) {
|
||||
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||
// Skip the command.
|
||||
for (++p; *p != 0; ++ p);
|
||||
// Skip the gaps.
|
||||
for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
|
||||
}
|
||||
}
|
||||
SERIAL_ECHOLNPGM("End of the buffer.");
|
||||
}
|
||||
}
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
|
||||
//adds an command to the main command buffer
|
||||
//thats really done in a non-safe way.
|
||||
//needs overworking someday
|
||||
// Currently the maximum length of a command piped through this function is around 20 characters
|
||||
void enquecommand(const char *cmd, bool from_progmem)
|
||||
{
|
||||
int len = from_progmem ? strlen_P(cmd) : strlen(cmd);
|
||||
// Does cmd fit the queue while leaving sufficient space at the front for the chained commands?
|
||||
// If it fits, it may move bufindw, so it points to a contiguous buffer, which fits cmd.
|
||||
if (cmdqueue_could_enqueue_back(len)) {
|
||||
// This is dangerous if a mixing of serial and this happens
|
||||
// This may easily be tested: If serial_count > 0, we have a problem.
|
||||
cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_UI;
|
||||
if (from_progmem)
|
||||
strcpy_P(cmdbuffer + bufindw + CMDHDRSIZE, cmd);
|
||||
else
|
||||
strcpy(cmdbuffer + bufindw + CMDHDRSIZE, cmd);
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_Enqueing);
|
||||
SERIAL_ECHO(cmdbuffer + bufindw + CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("\"");
|
||||
bufindw += len + (CMDHDRSIZE + 1);
|
||||
if (bufindw == sizeof(cmdbuffer))
|
||||
bufindw = 0;
|
||||
++ buflen;
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
cmdqueue_dump_to_serial();
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
} else {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ECHORPGM(MSG_Enqueing);
|
||||
if (from_progmem)
|
||||
SERIAL_PROTOCOLRPGM(cmd);
|
||||
else
|
||||
SERIAL_ECHO(cmd);
|
||||
SERIAL_ECHOLNPGM("\" failed: Buffer full!");
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
cmdqueue_dump_to_serial();
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
}
|
||||
}
|
||||
|
||||
bool cmd_buffer_empty()
|
||||
{
|
||||
return (buflen == 0);
|
||||
}
|
||||
|
||||
void enquecommand_front(const char *cmd, bool from_progmem)
|
||||
{
|
||||
int len = from_progmem ? strlen_P(cmd) : strlen(cmd);
|
||||
// Does cmd fit the queue? This call shall move bufindr, so the command may be copied.
|
||||
if (cmdqueue_could_enqueue_front(len)) {
|
||||
cmdbuffer[bufindr] = CMDBUFFER_CURRENT_TYPE_UI;
|
||||
if (from_progmem)
|
||||
strcpy_P(cmdbuffer + bufindr + CMDHDRSIZE, cmd);
|
||||
else
|
||||
strcpy(cmdbuffer + bufindr + CMDHDRSIZE, cmd);
|
||||
++ buflen;
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOPGM("Enqueing to the front: \"");
|
||||
SERIAL_ECHO(cmdbuffer + bufindr + CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("\"");
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
cmdqueue_dump_to_serial();
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
} else {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ECHOPGM("Enqueing to the front: \"");
|
||||
if (from_progmem)
|
||||
SERIAL_PROTOCOLRPGM(cmd);
|
||||
else
|
||||
SERIAL_ECHO(cmd);
|
||||
SERIAL_ECHOLNPGM("\" failed: Buffer full!");
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
cmdqueue_dump_to_serial();
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
}
|
||||
}
|
||||
|
||||
// Mark the command at the top of the command queue as new.
|
||||
// Therefore it will not be removed from the queue.
|
||||
void repeatcommand_front()
|
||||
{
|
||||
cmdbuffer_front_already_processed = true;
|
||||
}
|
||||
|
||||
bool is_buffer_empty()
|
||||
{
|
||||
if (buflen == 0) return true;
|
||||
else return false;
|
||||
}
|
||||
|
||||
void get_command()
|
||||
{
|
||||
// Test and reserve space for the new command string.
|
||||
if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE - 1, true))
|
||||
return;
|
||||
|
||||
bool rx_buffer_full = false; //flag that serial rx buffer is full
|
||||
|
||||
while (MYSERIAL.available() > 0) {
|
||||
if (MYSERIAL.available() == RX_BUFFER_SIZE - 1) { //compare number of chars buffered in rx buffer with rx buffer size
|
||||
SERIAL_ECHOLNPGM("Full RX Buffer"); //if buffer was full, there is danger that reading of last gcode will not be completed
|
||||
rx_buffer_full = true; //sets flag that buffer was full
|
||||
}
|
||||
char serial_char = MYSERIAL.read();
|
||||
if (selectedSerialPort == 1)
|
||||
{
|
||||
selectedSerialPort = 0;
|
||||
MYSERIAL.write(serial_char); // for debuging serial line 2 in farm_mode
|
||||
selectedSerialPort = 1;
|
||||
}
|
||||
TimeSent = millis();
|
||||
TimeNow = millis();
|
||||
|
||||
if (serial_char < 0)
|
||||
// Ignore extended ASCII characters. These characters have no meaning in the G-code apart from the file names
|
||||
// and Marlin does not support such file names anyway.
|
||||
// Serial characters with a highest bit set to 1 are generated when the USB cable is unplugged, leading
|
||||
// to a hang-up of the print process from an SD card.
|
||||
continue;
|
||||
if(serial_char == '\n' ||
|
||||
serial_char == '\r' ||
|
||||
(serial_char == ':' && comment_mode == false) ||
|
||||
serial_count >= (MAX_CMD_SIZE - 1) )
|
||||
{
|
||||
if(!serial_count) { //if empty line
|
||||
comment_mode = false; //for new command
|
||||
return;
|
||||
}
|
||||
cmdbuffer[bufindw+serial_count+CMDHDRSIZE] = 0; //terminate string
|
||||
if(!comment_mode){
|
||||
comment_mode = false; //for new command
|
||||
if ((strchr_pointer = strstr(cmdbuffer+bufindw+CMDHDRSIZE, "PRUSA")) == NULL && (strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, 'N')) != NULL) {
|
||||
if ((strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, 'N')) != NULL)
|
||||
{
|
||||
// Line number met. When sending a G-code over a serial line, each line may be stamped with its index,
|
||||
// and Marlin tests, whether the successive lines are stamped with an increasing line number ID.
|
||||
gcode_N = (strtol(strchr_pointer+1, NULL, 10));
|
||||
if(gcode_N != gcode_LastN+1 && (strstr_P(cmdbuffer+bufindw+CMDHDRSIZE, PSTR("M110")) == NULL) ) {
|
||||
// M110 - set current line number.
|
||||
// Line numbers not sent in succession.
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_LINE_NO);
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
//Serial.println(gcode_N);
|
||||
FlushSerialRequestResend();
|
||||
serial_count = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
if((strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, '*')) != NULL)
|
||||
{
|
||||
byte checksum = 0;
|
||||
char *p = cmdbuffer+bufindw+CMDHDRSIZE;
|
||||
while (p != strchr_pointer)
|
||||
checksum = checksum^(*p++);
|
||||
if (int(strtol(strchr_pointer+1, NULL, 10)) != int(checksum)) {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_CHECKSUM_MISMATCH);
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
FlushSerialRequestResend();
|
||||
serial_count = 0;
|
||||
return;
|
||||
}
|
||||
// If no errors, remove the checksum and continue parsing.
|
||||
*strchr_pointer = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_NO_CHECKSUM);
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
FlushSerialRequestResend();
|
||||
serial_count = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
gcode_LastN = gcode_N;
|
||||
//if no errors, continue parsing
|
||||
} // end of 'N' command
|
||||
}
|
||||
else // if we don't receive 'N' but still see '*'
|
||||
{
|
||||
if((strchr(cmdbuffer+bufindw+CMDHDRSIZE, '*') != NULL))
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
serial_count = 0;
|
||||
return;
|
||||
}
|
||||
} // end of '*' command
|
||||
if ((strchr_pointer = strchr(cmdbuffer+bufindw+CMDHDRSIZE, 'G')) != NULL) {
|
||||
if (! IS_SD_PRINTING) {
|
||||
usb_printing_counter = 10;
|
||||
is_usb_printing = true;
|
||||
}
|
||||
if (Stopped == true) {
|
||||
int gcode = strtol(strchr_pointer+1, NULL, 10);
|
||||
if (gcode >= 0 && gcode <= 3) {
|
||||
SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
|
||||
LCD_MESSAGERPGM(MSG_STOPPED);
|
||||
}
|
||||
}
|
||||
} // end of 'G' command
|
||||
|
||||
//If command was e-stop process now
|
||||
if(strcmp(cmdbuffer+bufindw+CMDHDRSIZE, "M112") == 0)
|
||||
kill("", 2);
|
||||
|
||||
// Store the current line into buffer, move to the next line.
|
||||
cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_USB;
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOPGM("Storing a command line to buffer: ");
|
||||
SERIAL_ECHO(cmdbuffer+bufindw+CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
bufindw += strlen(cmdbuffer+bufindw+CMDHDRSIZE) + (1 + CMDHDRSIZE);
|
||||
if (bufindw == sizeof(cmdbuffer))
|
||||
bufindw = 0;
|
||||
++ buflen;
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
SERIAL_ECHOPGM("Number of commands in the buffer: ");
|
||||
SERIAL_ECHO(buflen);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
} // end of 'not comment mode'
|
||||
serial_count = 0; //clear buffer
|
||||
// Don't call cmdqueue_could_enqueue_back if there are no characters waiting
|
||||
// in the queue, as this function will reserve the memory.
|
||||
if (MYSERIAL.available() == 0 || ! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1, true))
|
||||
return;
|
||||
} // end of "end of line" processing
|
||||
else {
|
||||
// Not an "end of line" symbol. Store the new character into a buffer.
|
||||
if(serial_char == ';') comment_mode = true;
|
||||
if(!comment_mode) cmdbuffer[bufindw+CMDHDRSIZE+serial_count++] = serial_char;
|
||||
}
|
||||
} // end of serial line processing loop
|
||||
|
||||
if(farm_mode){
|
||||
TimeNow = millis();
|
||||
if ( ((TimeNow - TimeSent) > 800) && (serial_count > 0) ) {
|
||||
cmdbuffer[bufindw+serial_count+CMDHDRSIZE] = 0;
|
||||
|
||||
bufindw += strlen(cmdbuffer+bufindw+CMDHDRSIZE) + (1 + CMDHDRSIZE);
|
||||
if (bufindw == sizeof(cmdbuffer))
|
||||
bufindw = 0;
|
||||
++ buflen;
|
||||
|
||||
serial_count = 0;
|
||||
|
||||
SERIAL_ECHOPGM("TIMEOUT:");
|
||||
//memset(cmdbuffer, 0 , sizeof(cmdbuffer));
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
//add comment
|
||||
if (rx_buffer_full == true && serial_count > 0) { //if rx buffer was full and string was not properly terminated
|
||||
rx_buffer_full = false;
|
||||
bufindw = bufindw - serial_count; //adjust tail of the buffer to prepare buffer for writing new command
|
||||
serial_count = 0;
|
||||
}
|
||||
|
||||
#ifdef SDSUPPORT
|
||||
if(!card.sdprinting || serial_count!=0){
|
||||
// If there is a half filled buffer from serial line, wait until return before
|
||||
// continuing with the serial line.
|
||||
return;
|
||||
}
|
||||
|
||||
//'#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible
|
||||
// if it occurs, stop_buffering is triggered and the buffer is ran dry.
|
||||
// this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing
|
||||
|
||||
static bool stop_buffering=false;
|
||||
if(buflen==0) stop_buffering=false;
|
||||
union {
|
||||
struct {
|
||||
char lo;
|
||||
char hi;
|
||||
} lohi;
|
||||
uint16_t value;
|
||||
} sd_count;
|
||||
sd_count.value = 0;
|
||||
// Reads whole lines from the SD card. Never leaves a half-filled line in the cmdbuffer.
|
||||
while( !card.eof() && !stop_buffering) {
|
||||
int16_t n=card.get();
|
||||
char serial_char = (char)n;
|
||||
if(serial_char == '\n' ||
|
||||
serial_char == '\r' ||
|
||||
((serial_char == '#' || serial_char == ':') && comment_mode == false) ||
|
||||
serial_count >= (MAX_CMD_SIZE - 1) || n==-1)
|
||||
{
|
||||
if(card.eof()){
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_FILE_PRINTED);
|
||||
stoptime=millis();
|
||||
char time[30];
|
||||
unsigned long t=(stoptime-starttime-pause_time)/1000;
|
||||
pause_time = 0;
|
||||
int hours, minutes;
|
||||
minutes=(t/60)%60;
|
||||
hours=t/60/60;
|
||||
save_statistics(total_filament_used, t);
|
||||
sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLN(time);
|
||||
lcd_setstatus(time);
|
||||
card.printingHasFinished();
|
||||
card.checkautostart(true);
|
||||
|
||||
if (farm_mode)
|
||||
{
|
||||
prusa_statistics(6);
|
||||
lcd_commands_type = LCD_COMMAND_FARM_MODE_CONFIRM;
|
||||
}
|
||||
|
||||
}
|
||||
if(serial_char=='#')
|
||||
stop_buffering=true;
|
||||
|
||||
if(!serial_count)
|
||||
{
|
||||
// This is either an empty line, or a line with just a comment.
|
||||
// Continue to the following line, and continue accumulating the number of bytes
|
||||
// read from the sdcard into sd_count,
|
||||
// so that the lenght of the already read empty lines and comments will be added
|
||||
// to the following non-empty line.
|
||||
comment_mode = false;
|
||||
continue; //if empty line
|
||||
}
|
||||
// The new command buffer could be updated non-atomically, because it is not yet considered
|
||||
// to be inside the active queue.
|
||||
sd_count.value = (card.get_sdpos()+1) - sdpos_atomic;
|
||||
cmdbuffer[bufindw] = CMDBUFFER_CURRENT_TYPE_SDCARD;
|
||||
cmdbuffer[bufindw+1] = sd_count.lohi.lo;
|
||||
cmdbuffer[bufindw+2] = sd_count.lohi.hi;
|
||||
cmdbuffer[bufindw+serial_count+CMDHDRSIZE] = 0; //terminate string
|
||||
// Calculate the length before disabling the interrupts.
|
||||
uint8_t len = strlen(cmdbuffer+bufindw+CMDHDRSIZE) + (1 + CMDHDRSIZE);
|
||||
|
||||
// SERIAL_ECHOPGM("SD cmd(");
|
||||
// MYSERIAL.print(sd_count.value, DEC);
|
||||
// SERIAL_ECHOPGM(") ");
|
||||
// SERIAL_ECHOLN(cmdbuffer+bufindw+CMDHDRSIZE);
|
||||
// SERIAL_ECHOPGM("cmdbuffer:");
|
||||
// MYSERIAL.print(cmdbuffer);
|
||||
// SERIAL_ECHOPGM("buflen:");
|
||||
// MYSERIAL.print(buflen+1);
|
||||
sd_count.value = 0;
|
||||
|
||||
cli();
|
||||
++ buflen;
|
||||
bufindw += len;
|
||||
sdpos_atomic = card.get_sdpos()+1;
|
||||
if (bufindw == sizeof(cmdbuffer))
|
||||
bufindw = 0;
|
||||
sei();
|
||||
|
||||
comment_mode = false; //for new command
|
||||
serial_count = 0; //clear buffer
|
||||
// The following line will reserve buffer space if available.
|
||||
if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1, true))
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
if(serial_char == ';') comment_mode = true;
|
||||
else if(!comment_mode) cmdbuffer[bufindw+CMDHDRSIZE+serial_count++] = serial_char;
|
||||
}
|
||||
}
|
||||
|
||||
#endif //SDSUPPORT
|
||||
}
|
||||
|
||||
uint16_t cmdqueue_calc_sd_length()
|
||||
{
|
||||
if (buflen == 0)
|
||||
return 0;
|
||||
union {
|
||||
struct {
|
||||
char lo;
|
||||
char hi;
|
||||
} lohi;
|
||||
uint16_t value;
|
||||
} sdlen_single;
|
||||
uint16_t sdlen = 0;
|
||||
for (int _buflen = buflen, _bufindr = bufindr;;) {
|
||||
if (cmdbuffer[_bufindr] == CMDBUFFER_CURRENT_TYPE_SDCARD) {
|
||||
sdlen_single.lohi.lo = cmdbuffer[_bufindr + 1];
|
||||
sdlen_single.lohi.hi = cmdbuffer[_bufindr + 2];
|
||||
sdlen += sdlen_single.value;
|
||||
}
|
||||
if (-- _buflen == 0)
|
||||
break;
|
||||
// First skip the current command ID and iterate up to the end of the string.
|
||||
for (_bufindr += CMDHDRSIZE; cmdbuffer[_bufindr] != 0; ++ _bufindr) ;
|
||||
// Second, skip the end of string null character and iterate until a nonzero command ID is found.
|
||||
for (++ _bufindr; _bufindr < sizeof(cmdbuffer) && cmdbuffer[_bufindr] == 0; ++ _bufindr) ;
|
||||
// If the end of the buffer was empty,
|
||||
if (_bufindr == sizeof(cmdbuffer)) {
|
||||
// skip to the start and find the nonzero command.
|
||||
for (_bufindr = 0; cmdbuffer[_bufindr] == 0; ++ _bufindr) ;
|
||||
}
|
||||
}
|
||||
return sdlen;
|
||||
}
|
89
Firmware/cmdqueue.h
Normal file
89
Firmware/cmdqueue.h
Normal file
|
@ -0,0 +1,89 @@
|
|||
#ifndef CMDQUEUE_H
|
||||
#define CMDQUEUE_H
|
||||
|
||||
#include "Marlin.h"
|
||||
#include "language_all.h"
|
||||
|
||||
|
||||
// String circular buffer. Commands may be pushed to the buffer from both sides:
|
||||
// Chained commands will be pushed to the front, interactive (from LCD menu)
|
||||
// and printing commands (from serial line or from SD card) are pushed to the tail.
|
||||
// First character of each entry indicates the type of the entry:
|
||||
#define CMDBUFFER_CURRENT_TYPE_UNKNOWN 0
|
||||
// Command in cmdbuffer was sent over USB.
|
||||
#define CMDBUFFER_CURRENT_TYPE_USB 1
|
||||
// Command in cmdbuffer was read from SDCARD.
|
||||
#define CMDBUFFER_CURRENT_TYPE_SDCARD 2
|
||||
// Command in cmdbuffer was generated by the UI.
|
||||
#define CMDBUFFER_CURRENT_TYPE_UI 3
|
||||
// Command in cmdbuffer was generated by another G-code.
|
||||
#define CMDBUFFER_CURRENT_TYPE_CHAINED 4
|
||||
|
||||
// How much space to reserve for the chained commands
|
||||
// of type CMDBUFFER_CURRENT_TYPE_CHAINED,
|
||||
// which are pushed to the front of the queue?
|
||||
// Maximum 5 commands of max length 20 + null terminator.
|
||||
#define CMDBUFFER_RESERVE_FRONT (5*21)
|
||||
|
||||
extern char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
|
||||
extern int bufindr;
|
||||
extern int bufindw;
|
||||
extern int buflen;
|
||||
extern bool cmdbuffer_front_already_processed;
|
||||
|
||||
// Type of a command, which is to be executed right now.
|
||||
#define CMDBUFFER_CURRENT_TYPE (cmdbuffer[bufindr])
|
||||
// String of a command, which is to be executed right now.
|
||||
#define CMDBUFFER_CURRENT_STRING (cmdbuffer+bufindr+CMDHDRSIZE)
|
||||
|
||||
// Enable debugging of the command buffer.
|
||||
// Debugging information will be sent to serial line.
|
||||
//#define CMDBUFFER_DEBUG
|
||||
|
||||
extern int serial_count;
|
||||
extern boolean comment_mode;
|
||||
extern char *strchr_pointer;
|
||||
|
||||
extern unsigned long TimeSent;
|
||||
extern unsigned long TimeNow;
|
||||
|
||||
extern long gcode_N;
|
||||
extern long gcode_LastN;
|
||||
extern long Stopped_gcode_LastN;
|
||||
|
||||
extern bool cmdqueue_pop_front();
|
||||
extern void cmdqueue_reset();
|
||||
extern bool cmdqueue_could_enqueue_front(int len_asked);
|
||||
extern bool cmdqueue_could_enqueue_back(int len_asked, bool atomic_update = false);
|
||||
#ifdef CMDBUFFER_DEBUG
|
||||
extern void cmdqueue_dump_to_serial_single_line(int nr, const char *p);
|
||||
extern void cmdqueue_dump_to_serial();
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
extern bool cmd_buffer_empty();
|
||||
extern void enquecommand(const char *cmd, bool from_progmem);
|
||||
extern void enquecommand_front(const char *cmd, bool from_progmem);
|
||||
extern void repeatcommand_front();
|
||||
extern bool is_buffer_empty();
|
||||
extern void get_command();
|
||||
extern uint16_t cmdqueue_calc_sd_length();
|
||||
|
||||
// Return True if a character was found
|
||||
static inline bool code_seen(char code) { return (strchr_pointer = strchr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
|
||||
static inline bool code_seen(const char *code) { return (strchr_pointer = strstr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
|
||||
static inline float code_value() { return strtod(strchr_pointer+1, NULL);}
|
||||
static inline long code_value_long() { return strtol(strchr_pointer+1, NULL, 10); }
|
||||
static inline int16_t code_value_short() { return int16_t(strtol(strchr_pointer+1, NULL, 10)); };
|
||||
static inline uint8_t code_value_uint8() { return uint8_t(strtol(strchr_pointer+1, NULL, 10)); };
|
||||
|
||||
static inline float code_value_float()
|
||||
{
|
||||
char* e = strchr(strchr_pointer, 'E');
|
||||
if (!e) return strtod(strchr_pointer + 1, NULL);
|
||||
*e = 0;
|
||||
float ret = strtod(strchr_pointer + 1, NULL);
|
||||
*e = 'E';
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
#endif //CMDQUEUE_H
|
199
Firmware/fsensor.cpp
Normal file
199
Firmware/fsensor.cpp
Normal file
|
@ -0,0 +1,199 @@
|
|||
#include "Marlin.h"
|
||||
|
||||
#ifdef PAT9125
|
||||
|
||||
#include "fsensor.h"
|
||||
#include "pat9125.h"
|
||||
#include "planner.h"
|
||||
#include "fastio.h"
|
||||
|
||||
//#include "LiquidCrystal.h"
|
||||
//extern LiquidCrystal lcd;
|
||||
|
||||
|
||||
#define FSENSOR_ERR_MAX 5 //filament sensor max error count
|
||||
#define FSENSOR_INT_PIN 63 //filament sensor interrupt pin PK1
|
||||
#define FSENSOR_INT_PIN_MSK 0x02 //filament sensor interrupt pin mask (bit1)
|
||||
#define FSENSOR_CHUNK_LEN 560 //filament sensor chunk length in steps
|
||||
|
||||
extern void stop_and_save_print_to_ram(float z_move, float e_move);
|
||||
extern void restore_print_from_ram_and_continue(float e_move);
|
||||
extern int8_t FSensorStateMenu;
|
||||
|
||||
void fsensor_stop_and_save_print()
|
||||
{
|
||||
stop_and_save_print_to_ram(0, 0); //XYZE - no change
|
||||
}
|
||||
|
||||
void fsensor_restore_print_and_continue()
|
||||
{
|
||||
restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change
|
||||
}
|
||||
|
||||
//uint8_t fsensor_int_pin = FSENSOR_INT_PIN;
|
||||
uint8_t fsensor_int_pin_old = 0;
|
||||
int16_t fsensor_chunk_len = FSENSOR_CHUNK_LEN;
|
||||
bool fsensor_enabled = true;
|
||||
//bool fsensor_ignore_error = true;
|
||||
bool fsensor_M600 = false;
|
||||
uint8_t fsensor_err_cnt = 0;
|
||||
int16_t fsensor_st_cnt = 0;
|
||||
uint8_t fsensor_log = 1;
|
||||
|
||||
|
||||
bool fsensor_enable()
|
||||
{
|
||||
puts_P(PSTR("fsensor_enable\n"));
|
||||
int pat9125 = pat9125_init(PAT9125_XRES, PAT9125_YRES);
|
||||
printf_P(PSTR("PAT9125_init:%d\n"), pat9125);
|
||||
fsensor_enabled = pat9125?true:false;
|
||||
// fsensor_ignore_error = true;
|
||||
fsensor_M600 = false;
|
||||
fsensor_err_cnt = 0;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, fsensor_enabled?0x01:0x00);
|
||||
FSensorStateMenu = fsensor_enabled?1:0;
|
||||
return fsensor_enabled;
|
||||
}
|
||||
|
||||
void fsensor_disable()
|
||||
{
|
||||
puts_P(PSTR("fsensor_disable\n"));
|
||||
fsensor_enabled = false;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0x00);
|
||||
FSensorStateMenu = 0;
|
||||
}
|
||||
|
||||
void pciSetup(byte pin)
|
||||
{
|
||||
*digitalPinToPCMSK(pin) |= bit (digitalPinToPCMSKbit(pin)); // enable pin
|
||||
PCIFR |= bit (digitalPinToPCICRbit(pin)); // clear any outstanding interrupt
|
||||
PCICR |= bit (digitalPinToPCICRbit(pin)); // enable interrupt for the group
|
||||
}
|
||||
|
||||
void fsensor_setup_interrupt()
|
||||
{
|
||||
// uint8_t fsensor_int_pin = FSENSOR_INT_PIN;
|
||||
// uint8_t fsensor_int_pcmsk = digitalPinToPCMSKbit(pin);
|
||||
// uint8_t fsensor_int_pcicr = digitalPinToPCICRbit(pin);
|
||||
|
||||
pinMode(FSENSOR_INT_PIN, OUTPUT);
|
||||
digitalWrite(FSENSOR_INT_PIN, LOW);
|
||||
fsensor_int_pin_old = 0;
|
||||
|
||||
pciSetup(FSENSOR_INT_PIN);
|
||||
}
|
||||
|
||||
ISR(PCINT2_vect)
|
||||
{
|
||||
// return;
|
||||
if (!((fsensor_int_pin_old ^ PINK) & FSENSOR_INT_PIN_MSK)) return;
|
||||
// puts("PCINT2\n");
|
||||
// return;
|
||||
|
||||
int st_cnt = fsensor_st_cnt;
|
||||
fsensor_st_cnt = 0;
|
||||
sei();
|
||||
/* *digitalPinToPCMSK(fsensor_int_pin) &= ~bit(digitalPinToPCMSKbit(fsensor_int_pin));
|
||||
digitalWrite(fsensor_int_pin, HIGH);
|
||||
*digitalPinToPCMSK(fsensor_int_pin) |= bit(digitalPinToPCMSKbit(fsensor_int_pin));*/
|
||||
pat9125_update_y();
|
||||
if (st_cnt != 0)
|
||||
{
|
||||
#ifdef DEBUG_FSENSOR_LOG
|
||||
if (fsensor_log)
|
||||
{
|
||||
MYSERIAL.print("cnt=");
|
||||
MYSERIAL.print(st_cnt, DEC);
|
||||
MYSERIAL.print(" dy=");
|
||||
MYSERIAL.print(pat9125_y, DEC);
|
||||
}
|
||||
#endif //DEBUG_FSENSOR_LOG
|
||||
if (st_cnt != 0)
|
||||
{
|
||||
if( (pat9125_y == 0) || ((pat9125_y > 0) && (st_cnt < 0)) || ((pat9125_y < 0) && (st_cnt > 0)))
|
||||
{ //invalid movement
|
||||
if (st_cnt > 0) //only positive movements
|
||||
fsensor_err_cnt++;
|
||||
#ifdef DEBUG_FSENSOR_LOG
|
||||
if (fsensor_log)
|
||||
{
|
||||
MYSERIAL.print("\tNG ! err=");
|
||||
MYSERIAL.println(fsensor_err_cnt, DEC);
|
||||
}
|
||||
#endif //DEBUG_FSENSOR_LOG
|
||||
}
|
||||
else
|
||||
{ //propper movement
|
||||
if (fsensor_err_cnt > 0)
|
||||
fsensor_err_cnt--;
|
||||
// fsensor_err_cnt = 0;
|
||||
#ifdef DEBUG_FSENSOR_LOG
|
||||
if (fsensor_log)
|
||||
{
|
||||
MYSERIAL.print("\tOK err=");
|
||||
MYSERIAL.println(fsensor_err_cnt, DEC);
|
||||
}
|
||||
#endif //DEBUG_FSENSOR_LOG
|
||||
}
|
||||
}
|
||||
else
|
||||
{ //no movement
|
||||
#ifdef DEBUG_FSENSOR_LOG
|
||||
if (fsensor_log)
|
||||
MYSERIAL.println("\tOK 0");
|
||||
#endif //DEBUG_FSENSOR_LOG
|
||||
}
|
||||
}
|
||||
pat9125_y = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
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)))
|
||||
{
|
||||
if (_READ(63)) _WRITE(63, LOW);
|
||||
else _WRITE(63, HIGH);
|
||||
}
|
||||
// PINK |= FSENSOR_INT_PIN_MSK; //toggle pin
|
||||
// _WRITE(fsensor_int_pin, LOW);
|
||||
}
|
||||
|
||||
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))
|
||||
{
|
||||
if (_READ(63)) _WRITE(63, LOW);
|
||||
else _WRITE(63, HIGH);
|
||||
}
|
||||
// PINK |= FSENSOR_INT_PIN_MSK; //toggle pin
|
||||
// _WRITE(fsensor_int_pin, LOW);
|
||||
}
|
||||
|
||||
void fsensor_update()
|
||||
{
|
||||
if (!fsensor_enabled) return;
|
||||
if (fsensor_err_cnt > FSENSOR_ERR_MAX)
|
||||
{
|
||||
MYSERIAL.println("fsensor_update (fsensor_err_cnt > FSENSOR_ERR_MAX)");
|
||||
/* if (fsensor_ignore_error)
|
||||
{
|
||||
MYSERIAL.println("fsensor_update - error ignored)");
|
||||
fsensor_ignore_error = false;
|
||||
}
|
||||
else*/
|
||||
{
|
||||
MYSERIAL.println("fsensor_update - ERROR!!!");
|
||||
fsensor_stop_and_save_print();
|
||||
enquecommand_front_P((PSTR("M600")));
|
||||
fsensor_M600 = true;
|
||||
fsensor_enabled = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif //PAT9125
|
32
Firmware/fsensor.h
Normal file
32
Firmware/fsensor.h
Normal file
|
@ -0,0 +1,32 @@
|
|||
#ifndef FSENSOR_H
|
||||
#define FSENSOR_H
|
||||
|
||||
#include "planner.h"
|
||||
|
||||
//save restore printing
|
||||
extern void fsensor_stop_and_save_print();
|
||||
extern void fsensor_restore_print_and_continue();
|
||||
|
||||
//enable/disable
|
||||
extern bool fsensor_enable();
|
||||
extern void fsensor_disable();
|
||||
|
||||
//update (perform M600 on filament runout)
|
||||
extern void fsensor_update();
|
||||
|
||||
//setup pin-change interrupt
|
||||
extern void fsensor_setup_interrupt();
|
||||
|
||||
//callbacks from stepper
|
||||
extern void fsensor_st_block_begin(block_t* bl);
|
||||
extern void fsensor_st_block_chunk(block_t* bl, int cnt);
|
||||
|
||||
//minimum meassured chunk length in steps
|
||||
extern int16_t fsensor_chunk_len;
|
||||
//M600 in progress
|
||||
extern bool fsensor_M600;
|
||||
//enable/disable flag
|
||||
extern bool fsensor_enabled;
|
||||
|
||||
|
||||
#endif //FSENSOR_H
|
|
@ -4,53 +4,168 @@
|
|||
use strict;
|
||||
use warnings;
|
||||
|
||||
my @langs = ("en","cz","it","es","pl");
|
||||
#my @langs = ("en","cz","it","es","de");
|
||||
my @langs = ("en","cz");
|
||||
|
||||
sub parselang
|
||||
{
|
||||
my ($filename) = @_;
|
||||
open(my $fh, '<:encoding(UTF-8)', $filename)
|
||||
# open(my $fh, '<', $filename)
|
||||
or die "Could not open file '$filename' $!";
|
||||
# Create a new hash reference.
|
||||
my $out = {};
|
||||
while (my $line = <$fh>) {
|
||||
chomp $line;
|
||||
next if (index($line, 'MSG') == -1);
|
||||
$line =~ /(?is)\#define\s*(\S*)\s*(.*)/;
|
||||
my $symbol = $1;
|
||||
my $v = $2;
|
||||
next if (index($line, 'define') == -1 || index($line, 'MSG') == -1);
|
||||
my $modifiers = {};
|
||||
my $symbol = '';
|
||||
my $value = '';
|
||||
if (index($line, 'define(') == -1) {
|
||||
# Extended definition, which specifies the string formatting.
|
||||
$line =~ /(?is)define\s*(\S*)\s*(.*)/;
|
||||
$symbol = "$1";
|
||||
$value = $2;
|
||||
} else {
|
||||
$line =~ /(?is)define\((.*)\)\s*(\S*)\s*(.*)/;
|
||||
my $options = $1;
|
||||
foreach my $key_value (split /,/, $options) {
|
||||
if ($key_value =~ /\s*(\S*)\s*=\s*(\S*)\s*/) {
|
||||
${$modifiers}{$1} = $2;
|
||||
}
|
||||
}
|
||||
$symbol = "$2";
|
||||
$value = $3;
|
||||
}
|
||||
next if (! defined $symbol or length($symbol) == 0);
|
||||
# Trim whitespaces from both sides
|
||||
$v =~ s/^\s+|\s+$//g;
|
||||
$value =~ s/^\s+|\s+$//g;
|
||||
#$string =~ s/" MACHINE_NAME "/Prusa i3/;
|
||||
$v =~ s/" FIRMWARE_URL "/https:\/\/github.com\/prusa3d\/Prusa-i3-Plus\//;
|
||||
$v =~ s/" PROTOCOL_VERSION "/1.0/;
|
||||
$v =~ s/" STRINGIFY\(EXTRUDERS\) "/1/;
|
||||
$v =~ s/" MACHINE_UUID "/00000000-0000-0000-0000-000000000000/;
|
||||
${$out}{$symbol} = $v;
|
||||
$value =~ s/" FIRMWARE_URL "/https:\/\/github.com\/prusa3d\/Prusa-i3-Plus\//;
|
||||
$value =~ s/" PROTOCOL_VERSION "/1.0/;
|
||||
$value =~ s/" STRINGIFY\(EXTRUDERS\) "/1/;
|
||||
$value =~ s/" MACHINE_UUID "/00000000-0000-0000-0000-000000000000/;
|
||||
${$out}{$symbol} = { value=>$value, %$modifiers };
|
||||
}
|
||||
return $out;
|
||||
}
|
||||
|
||||
sub pgm_is_whitespace
|
||||
{
|
||||
my ($c) = @_;
|
||||
if (! defined($c)) {
|
||||
print "pgm_is_whitespace: undefined\n";
|
||||
exit(1);
|
||||
}
|
||||
return $c == ord(' ') || $c == ord('\t') || $c == ord('\r') || $c == ord('\n');
|
||||
}
|
||||
|
||||
sub pgm_is_interpunction
|
||||
{
|
||||
my ($c) = @_;
|
||||
return $c == ord('.') || $c == ord(',') || $c == ord(':') || $c == ord(';') || $c == ord('?') || $c == ord('!') || $c == ord('/');
|
||||
}
|
||||
|
||||
sub break_text_fullscreen
|
||||
{
|
||||
my $lines = [];
|
||||
my ($text_str, $max_linelen) = @_;
|
||||
if (! defined($text_str) || length($text_str) < 2) {
|
||||
return $lines;
|
||||
}
|
||||
$text_str =~ s/^"//;
|
||||
$text_str =~ s/([^\\])"/$1/;
|
||||
$text_str =~ s/\\"/"/;
|
||||
|
||||
my @msg = unpack("W*", $text_str);
|
||||
#my @msg = split("", $text_str);
|
||||
my $len = $#msg + 1;
|
||||
my $i = 0;
|
||||
|
||||
LINE:
|
||||
while ($i < $len) {
|
||||
while ($i < $len && pgm_is_whitespace($msg[$i])) {
|
||||
$i += 1;
|
||||
}
|
||||
if ($i == $len) {
|
||||
# End of the message.
|
||||
last LINE;
|
||||
}
|
||||
my $msgend2 = $i + (($max_linelen > $len) ? $len : $max_linelen);
|
||||
my $msgend = $msgend2;
|
||||
if ($msgend < $len && ! pgm_is_whitespace($msg[$msgend]) && ! pgm_is_interpunction($msg[$msgend])) {
|
||||
# Splitting a word. Find the start of the current word.
|
||||
while ($msgend > $i && ! pgm_is_whitespace($msg[$msgend - 1])) {
|
||||
$msgend -= 1;
|
||||
}
|
||||
if ($msgend == $i) {
|
||||
# Found a single long word, which cannot be split. Just cut it.
|
||||
$msgend = $msgend2;
|
||||
}
|
||||
}
|
||||
my $outstr = substr($text_str, $i, $msgend - $i);
|
||||
$i = $msgend;
|
||||
$outstr =~ s/~/ /g;
|
||||
#print "Output string: $outstr \n";
|
||||
push @$lines, $outstr;
|
||||
}
|
||||
|
||||
return $lines;
|
||||
}
|
||||
|
||||
my %texts;
|
||||
my %attributes;
|
||||
my $num_languages = 0;
|
||||
if (1)
|
||||
{
|
||||
# First load the common strings.
|
||||
my $symbols = parselang("language_common.h");
|
||||
foreach my $key (keys %{$symbols}) {
|
||||
if (! (exists $texts{$key})) {
|
||||
my $symbol_value = ${$symbols}{$key};
|
||||
# Store the symbol value for each language.
|
||||
$texts{$key} = [ (${$symbol_value}{value}) x ($#langs+1) ];
|
||||
# Store the possible attributes.
|
||||
delete ${$symbol_value}{value};
|
||||
# Store an "is common" attribute.
|
||||
${$symbol_value}{common} = 1;
|
||||
# 4x 80 characters, 4 lines sent over serial line.
|
||||
${$symbol_value}{length} = 320;
|
||||
${$symbol_value}{lines} = 1;
|
||||
$attributes{$key} = $symbol_value;
|
||||
} else {
|
||||
print "Duplicate key in language_common.h: $key\n";
|
||||
}
|
||||
}
|
||||
}
|
||||
foreach my $lang (@langs) {
|
||||
my $symbols = parselang("language_$lang.h");
|
||||
foreach my $key (keys %{$symbols}) {
|
||||
if (! (exists $texts{$key})) {
|
||||
$texts{$key} = [];
|
||||
}
|
||||
my $symbol_value = ${$symbols}{$key};
|
||||
my $strings = $texts{$key};
|
||||
die "Symbol $key defined first in $lang, undefined in the preceding language files."
|
||||
if (scalar(@$strings) != $num_languages);
|
||||
push @$strings, ${$symbols}{$key};
|
||||
if (defined $attributes{$key} && defined ${$attributes{$key}}{common} && ${$attributes{$key}}{common} == 1) {
|
||||
# Common overrides the possible definintions in the language specific files.
|
||||
} else {
|
||||
die "Symbol $key defined first in $lang, undefined in the preceding language files."
|
||||
if (scalar(@$strings) != $num_languages);
|
||||
push @$strings, ${$symbol_value}{value};
|
||||
if ($lang eq 'en') {
|
||||
# The english texts may contain attributes. Store them into %attributes.
|
||||
delete ${$symbol_value}{value};
|
||||
$attributes{$key} = $symbol_value;
|
||||
}
|
||||
}
|
||||
}
|
||||
$num_languages += 1;
|
||||
foreach my $key (keys %texts) {
|
||||
my $strings = $texts{$key};
|
||||
if (scalar(@$strings) != $num_languages) {
|
||||
if (scalar(@$strings) < $num_languages) {
|
||||
# die "Symbol $key undefined in $lang."
|
||||
print "Symbol $key undefined in $lang. Using the english variant.\n";
|
||||
print "Symbol $key undefined in language \"$lang\". Using the english variant:\n";
|
||||
print "\t", ${$strings}[0], "\n";
|
||||
push @$strings, ${$strings}[0];
|
||||
}
|
||||
}
|
||||
|
@ -66,8 +181,30 @@ print $fh <<END
|
|||
#ifndef LANGUAGE_ALL_H
|
||||
#define LANGUAGE_ALL_H
|
||||
|
||||
#define LANG_NUM (${num_languages})
|
||||
#include <avr/pgmspace.h>
|
||||
// Language indices into their particular symbol tables.
|
||||
END
|
||||
;
|
||||
|
||||
# Export symbolic IDs of languages.
|
||||
for my $i (0 .. $#langs) {
|
||||
my $lang = uc $langs[$i];
|
||||
print $fh "#define LANG_ID_$lang $i\n";
|
||||
}
|
||||
|
||||
print $fh <<END
|
||||
// Language is not defined and it shall be selected from the menu.
|
||||
#define LANG_ID_FORCE_SELECTION 254
|
||||
// Language is not defined on a virgin RAMBo board.
|
||||
#define LANG_ID_UNDEFINED 255
|
||||
|
||||
// Default language ID, if no language is selected.
|
||||
#define LANG_ID_DEFAULT LANG_ID_CZ
|
||||
|
||||
// Number of languages available in the language table.
|
||||
#define LANG_NUM ${num_languages}
|
||||
|
||||
// Currectly active language selection.
|
||||
extern unsigned char lang_selected;
|
||||
|
||||
#define LANG_TABLE_SELECT_EXPLICIT(TABLE, LANG) ((const char*)(pgm_read_ptr(TABLE + (LANG))))
|
||||
|
@ -77,10 +214,17 @@ END
|
|||
;
|
||||
|
||||
foreach my $key (sort(keys %texts)) {
|
||||
print $fh "extern const char* const ${key}_LANG_TABLE[LANG_NUM];\n";
|
||||
print $fh "#define $key LANG_TABLE_SELECT(${key}_LANG_TABLE)\n";
|
||||
print $fh "#define ${key}_EXPLICIT(LANG) LANG_TABLE_SELECT_EXPLICIT(${key}_LANG_TABLE, LANG)\n"
|
||||
if ($key eq "MSG_LANGUAGE_NAME" || $key eq "MSG_LANGUAGE_SELECT");
|
||||
my $strings = $texts{$key};
|
||||
if (@{$strings} == grep { $_ eq ${$strings}[0] } @{$strings}) {
|
||||
# All strings are English.
|
||||
print $fh "extern const char* const ${key}_LANG_TABLE[1];\n";
|
||||
print $fh "#define $key LANG_TABLE_SELECT_EXPLICIT(${key}_LANG_TABLE, 0)\n";
|
||||
} else {
|
||||
print $fh "extern const char* const ${key}_LANG_TABLE[LANG_NUM];\n";
|
||||
print $fh "#define $key LANG_TABLE_SELECT(${key}_LANG_TABLE)\n";
|
||||
print $fh "#define ${key}_EXPLICIT(LANG) LANG_TABLE_SELECT_EXPLICIT(${key}_LANG_TABLE, LANG)\n"
|
||||
if ($key eq "MSG_LANGUAGE_NAME" || $key eq "MSG_LANGUAGE_SELECT");
|
||||
}
|
||||
}
|
||||
|
||||
print $fh <<END
|
||||
|
@ -100,8 +244,8 @@ $filename = 'language_all.cpp';
|
|||
open($fh, '>', $filename) or die "Could not open file '$filename' $!";
|
||||
|
||||
print $fh <<'END'
|
||||
#include <avr/pgmspace.h>
|
||||
#include "configuration_prusa.h"
|
||||
|
||||
#include "Configuration_prusa.h"
|
||||
#include "language_all.h"
|
||||
|
||||
#define LCD_WIDTH 20
|
||||
|
@ -110,16 +254,31 @@ extern unsigned char lang_selected;
|
|||
END
|
||||
;
|
||||
|
||||
foreach my $key (sort(keys %texts)) {
|
||||
my @keys = sort(keys %texts);
|
||||
foreach my $key (@keys) {
|
||||
my $strings = $texts{$key};
|
||||
for (my $i = 0; $i <= $#{$strings}; $i ++) {
|
||||
my $suffix = uc($langs[$i]);
|
||||
print $fh "const char ${key}_${suffix}[] PROGMEM = ${$strings}[$i];\n";
|
||||
if (@{$strings} == grep { $_ eq ${$strings}[0] } @{$strings}) {
|
||||
# Shrink the array to a single value.
|
||||
$strings = [${$strings}[0]];
|
||||
}
|
||||
print $fh "const char * const ${key}_LANG_TABLE[LANG_NUM] PROGMEM = {\n";
|
||||
for (my $i = 0; $i <= $#{$strings}; $i ++) {
|
||||
my $suffix = uc($langs[$i]);
|
||||
print $fh "\t${key}_${suffix}";
|
||||
if ($i == 0 || ${$strings}[$i] ne ${$strings}[0]) {
|
||||
print $fh "const char ${key}_${suffix}[] PROGMEM = ${$strings}[$i];\n";
|
||||
}
|
||||
}
|
||||
my $langnum = $#{$strings}+1;
|
||||
if ($langnum == $#langs+1) {
|
||||
$langnum = "LANG_NUM";
|
||||
}
|
||||
print $fh "const char * const ${key}_LANG_TABLE[$langnum] PROGMEM = {\n";
|
||||
for (my $i = 0; $i <= $#{$strings}; $i ++) {
|
||||
my $suffix = uc($langs[$i]);
|
||||
if ($i == 0 || ${$strings}[$i] ne ${$strings}[0]) {
|
||||
print $fh "\t${key}_${suffix}";
|
||||
} else {
|
||||
print $fh "\t${key}_EN";
|
||||
}
|
||||
print $fh ',' if $i < $#{$strings};
|
||||
print $fh "\n";
|
||||
}
|
||||
|
@ -151,3 +310,41 @@ END
|
|||
;
|
||||
|
||||
print ".cpp created.\nDone!\n";
|
||||
|
||||
my $verify_only = 1;
|
||||
|
||||
for my $lang (0 .. $#langs) {
|
||||
print "Language: $langs[$lang]\n";
|
||||
foreach my $key (@keys) {
|
||||
my $strings = $texts{$key};
|
||||
my %attrib = %{$attributes{$key}};
|
||||
my $message = ${$strings}[$lang];
|
||||
$message =~ /\S*"(.*)"\S*/;
|
||||
$message = $1;
|
||||
if ($lang == 0 || ${$strings}[0] ne $message) {
|
||||
# If the language is not English, don't show the non-translated message.
|
||||
my $max_nlines = $attrib{lines} // 1;
|
||||
my $max_linelen = $attrib{length} // (($max_nlines > 1) ? 20 : 17);
|
||||
# if (! $verify_only) {
|
||||
# if ($nlines > 1) {
|
||||
# print "Multi-line message: $message. Breaking to $nlines lines:\n";
|
||||
# print "\t$_\n" foreach (@{$lines});
|
||||
# }
|
||||
# }
|
||||
if ($max_nlines <= 1) {
|
||||
my $linelen = length($message);
|
||||
if ($linelen > $max_linelen) {
|
||||
print "Key $key, language $langs[$lang], line length: $linelen, max length: $max_linelen\n";
|
||||
print "\t$message\n";
|
||||
}
|
||||
} else {
|
||||
my $lines = break_text_fullscreen($message, $max_linelen);
|
||||
my $nlines = @{$lines};
|
||||
if ($nlines > $max_nlines) {
|
||||
print "Key $key, language $langs[$lang], lines: $nlines, max lines: $max_nlines\n";
|
||||
print "\t$_\n" foreach (@{$lines});
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,32 +1,6 @@
|
|||
#ifndef LANGUAGE_H
|
||||
#define LANGUAGE_H
|
||||
|
||||
#define LANGUAGE_CONCAT(M) #M
|
||||
#define GENERATE_LANGUAGE_INCLUDE(M) LANGUAGE_CONCAT(language_##M.h)
|
||||
|
||||
|
||||
// NOTE: IF YOU CHANGE LANGUAGE FILES OR MERGE A FILE WITH CHANGES
|
||||
//
|
||||
// ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
|
||||
// ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS
|
||||
|
||||
// Languages
|
||||
// en English
|
||||
// pl Polish
|
||||
// fr French
|
||||
// de German
|
||||
// es Spanish
|
||||
// ru Russian
|
||||
// it Italian
|
||||
// pt Portuguese
|
||||
// fi Finnish
|
||||
// an Aragonese
|
||||
// nl Dutch
|
||||
// ca Catalan
|
||||
// eu Basque-Euskera
|
||||
|
||||
|
||||
|
||||
#define PROTOCOL_VERSION "1.0"
|
||||
|
||||
#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
|
||||
|
@ -66,10 +40,6 @@
|
|||
#define STRINGIFY(n) STRINGIFY_(n)
|
||||
|
||||
|
||||
// Common LCD messages
|
||||
|
||||
/* nothing here yet */
|
||||
|
||||
// Common serial messages
|
||||
#define MSG_MARLIN "Marlin"
|
||||
|
||||
|
@ -77,9 +47,6 @@
|
|||
|
||||
|
||||
// LCD Menu Messages
|
||||
|
||||
//#include LANGUAGE_INCLUDE
|
||||
|
||||
#include "language_all.h"
|
||||
|
||||
#endif //__LANGUAGE_H
|
||||
|
|
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
110
Firmware/language_common.h
Normal file
110
Firmware/language_common.h
Normal file
|
@ -0,0 +1,110 @@
|
|||
// These are the system messages, which shall always be in English.
|
||||
|
||||
+define MSG_Enqueing "enqueing \""
|
||||
+define MSG_POWERUP "PowerUp"
|
||||
define MSG_EXTERNAL_RESET " External Reset"
|
||||
define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
define MSG_SOFTWARE_RESET " Software Reset"
|
||||
define MSG_AUTHOR " | Author: "
|
||||
+define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
+define MSG_FREE_MEMORY " Free Memory: "
|
||||
+define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
+define MSG_OK "ok"
|
||||
define MSG_FILE_SAVED "Done saving file."
|
||||
define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
+define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
+define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
define MSG_FILE_PRINTED "Done printing file"
|
||||
+define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
+define MSG_END_FILE_LIST "End file list"
|
||||
+define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
+define MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
+define MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
+define MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
+define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
+define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
+define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
+define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
define MSG_COUNT_X " Count X: "
|
||||
+define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
+define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
+define MSG_RESEND "Resend: "
|
||||
define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
|
||||
define MSG_X_MIN "x_min: "
|
||||
define MSG_X_MAX "x_max: "
|
||||
define MSG_Y_MIN "y_min: "
|
||||
define MSG_Y_MAX "y_max: "
|
||||
define MSG_Z_MIN "z_min: "
|
||||
define MSG_Z_MAX "z_max: "
|
||||
|
||||
+define MSG_M119_REPORT "Reporting endstop status"
|
||||
+define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
+define MSG_ENDSTOP_OPEN "open"
|
||||
+define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
+define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
+define MSG_SD_INIT_FAIL "SD init fail"
|
||||
+define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
+define MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
+define MSG_SD_CARD_OK "SD card ok"
|
||||
+define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
+define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
+define MSG_SD_FILE_OPENED "File opened: "
|
||||
define MSG_SD_SIZE " Size: "
|
||||
+define MSG_SD_FILE_SELECTED "File selected"
|
||||
+define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
+define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
+define MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
+define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
+define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
+define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
+define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
+define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
+define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
+define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
+define MSG_BABYSTEPPING_Z "Adjusting Z"
|
||||
+define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
+define MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
+define MSG_SET_ORIGIN "Set origin"
|
||||
define MSG_ON "On "
|
||||
define MSG_OFF "Off"
|
||||
|
||||
+define MSG_VMIN "Vmin"
|
||||
+define MSG_VTRAV_MIN "VTrav min"
|
||||
+define MSG_AMAX "Amax "
|
||||
+define MSG_A_RETRACT "A-retract"
|
||||
+define MSG_MOVE_01MM "Move 0.1mm"
|
||||
+define MSG_MOVE_1MM "Move 1mm"
|
||||
+define MSG_MOVE_10MM "Move 10mm"
|
||||
|
||||
|
||||
+define MSG_NOZZLE1 "Nozzle2"
|
||||
+define MSG_NOZZLE2 "Nozzle3"
|
||||
+define MSG_FLOW0 "Flow 0"
|
||||
+define MSG_FLOW1 "Flow 1"
|
||||
+define MSG_FLOW2 "Flow 2"
|
||||
+define MSG_CONTROL "Control"
|
||||
+define MSG_MIN " \002 Min"
|
||||
+define MSG_MAX " \002 Max"
|
||||
+define MSG_FACTOR " \002 Fact"
|
||||
+define MSG_MOTION "Motion"
|
||||
+define MSG_VOLUMETRIC "Filament"
|
||||
+define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
+define MSG_STORE_EPROM "Store memory"
|
||||
+define MSG_LOAD_EPROM "Load memory"
|
||||
+define MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
+define MSG_REFRESH "\xF8" "Refresh"
|
||||
|
||||
+define MSG_INIT_SDCARD "Init. SD card"
|
||||
+define MSG_CNG_SDCARD "Change SD card"
|
||||
define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
+define MSG_BABYSTEP_X "Babystep X"
|
||||
+define MSG_BABYSTEP_Y "Babystep Y"
|
||||
+define MSG_RECTRACT "Rectract"
|
|
@ -5,47 +5,22 @@
|
|||
* Please note these are limited to 17 characters!
|
||||
*
|
||||
*/
|
||||
#ifndef LANGUAGE_CZ_H
|
||||
#define LANGUAGE_CZ_H
|
||||
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " ok"
|
||||
#define MSG_SD_INSERTED "Karta vlozena"
|
||||
#define MSG_SD_REMOVED "Karta vyjmuta"
|
||||
#define MSG_MAIN "Hlavni nabidka"
|
||||
#define MSG_AUTOSTART "Autostart"
|
||||
#define MSG_DISABLE_STEPPERS "Vypnout motory"
|
||||
#define MSG_AUTO_HOME "Auto home"
|
||||
#define MSG_SET_HOME_OFFSETS "Nastav pocatek home"
|
||||
#define MSG_SET_ORIGIN "Nastav pocatek"
|
||||
#define MSG_PREHEAT_PLA "Predehrev PLA"
|
||||
#define MSG_PREHEAT_PLA0 "Predehrev PLA 1"
|
||||
#define MSG_PREHEAT_PLA1 "Predehrev PLA 2"
|
||||
#define MSG_PREHEAT_PLA2 "Predehrev PLA 3"
|
||||
#define MSG_PREHEAT_PLA012 "Predehrev PLA All"
|
||||
#define MSG_PREHEAT_PLA_BEDONLY "Predehrev PLA Bed"
|
||||
#define MSG_PREHEAT_PLA_SETTINGS "Predehrev PLA conf"
|
||||
#define MSG_PREHEAT_ABS "Predehrev ABS"
|
||||
#define MSG_PREHEAT_ABS0 "Predehrev ABS 1"
|
||||
#define MSG_PREHEAT_ABS1 "Predehrev ABS 2"
|
||||
#define MSG_PREHEAT_ABS2 "Predehrev ABS 3"
|
||||
#define MSG_PREHEAT_ABS012 "Predehrev ABS All"
|
||||
#define MSG_PREHEAT_ABS_BEDONLY "Predehrev ABS Bed"
|
||||
#define MSG_PREHEAT_ABS_SETTINGS "Predehrev ABS conf"
|
||||
#define MSG_COOLDOWN "Zchladit"
|
||||
#define MSG_SWITCH_PS_ON "Vypnout zdroj"
|
||||
#define MSG_SWITCH_PS_OFF "Zapnout zdroj"
|
||||
#define MSG_EXTRUDE "Extrudovat"
|
||||
#define MSG_RETRACT "Retract"
|
||||
#define MSG_MOVE_AXIS "Posunout osu"
|
||||
#define MSG_MOVE_X "Posunout X"
|
||||
#define MSG_MOVE_Y "Posunout Y"
|
||||
#define MSG_MOVE_Z "Posunout Z"
|
||||
#define MSG_MOVE_E "Extruder"
|
||||
#define MSG_MOVE_E1 "Extruder2"
|
||||
#define MSG_MOVE_E2 "Extruder3"
|
||||
#define MSG_MOVE_01MM "Posunout o 0.1mm"
|
||||
#define MSG_MOVE_1MM "Posunout o 1mm"
|
||||
#define MSG_MOVE_10MM "Posunout o 10mm"
|
||||
#define MSG_SPEED "Rychlost"
|
||||
#define MSG_NOZZLE "Tryska"
|
||||
#define MSG_NOZZLE1 "Tryska2"
|
||||
|
@ -60,44 +35,15 @@
|
|||
#define MSG_MIN " \002 Min"
|
||||
#define MSG_MAX " \002 Max"
|
||||
#define MSG_FACTOR " \002 Fact"
|
||||
#define MSG_AUTOTEMP "Autotemp"
|
||||
#define MSG_ON "On "
|
||||
#define MSG_OFF "Off"
|
||||
#define MSG_PID_P "PID-P"
|
||||
#define MSG_PID_I "PID-I"
|
||||
#define MSG_PID_D "PID-D"
|
||||
#define MSG_PID_C "PID-C"
|
||||
#define MSG_ACC "Accel"
|
||||
#define MSG_VXY_JERK "Vxy-jerk"
|
||||
#define MSG_VZ_JERK "Vz-jerk"
|
||||
#define MSG_VE_JERK "Ve-jerk"
|
||||
#define MSG_VMAX "Vmax "
|
||||
#define MSG_X "x"
|
||||
#define MSG_Y "y"
|
||||
#define MSG_Z "z"
|
||||
#define MSG_E "e"
|
||||
#define MSG_VMIN "Vmin"
|
||||
#define MSG_VTRAV_MIN "VTrav min"
|
||||
#define MSG_AMAX "Amax "
|
||||
#define MSG_A_RETRACT "A-retract"
|
||||
#define MSG_XSTEPS "Xsteps/mm"
|
||||
#define MSG_YSTEPS "Ysteps/mm"
|
||||
#define MSG_ZSTEPS "Zsteps/mm"
|
||||
#define MSG_ESTEPS "Esteps/mm"
|
||||
#define MSG_TEMPERATURE "Teplota"
|
||||
#define MSG_MOTION "Pohyb"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
|
||||
#define MSG_CONTRAST "LCD contrast"
|
||||
#define MSG_STORE_EPROM "Store memory"
|
||||
#define MSG_LOAD_EPROM "Ulozit pamet"
|
||||
#define MSG_RESTORE_FAILSAFE "Obnovit vychozi"
|
||||
#define MSG_REFRESH "\xF8" "Obnovit"
|
||||
#define MSG_WATCH "Informace"
|
||||
#define MSG_PREPARE "Priprava"
|
||||
#define MSG_TUNE "Ladit"
|
||||
#define MSG_PAUSE_PRINT "Pozastavit tisk"
|
||||
#define MSG_RESUME_PRINT "Pokracovat"
|
||||
|
@ -111,24 +57,12 @@
|
|||
#define MSG_NO_MOVE "No move."
|
||||
#define MSG_KILLED "KILLED. "
|
||||
#define MSG_STOPPED "STOPPED. "
|
||||
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
|
||||
#define MSG_CONTROL_RETRACTF "Retract V"
|
||||
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
|
||||
#define MSG_AUTORETRACT "AutoRetr."
|
||||
#define MSG_FILAMENTCHANGE "Vymenit filament"
|
||||
#define MSG_INIT_SDCARD "Inic. SD"
|
||||
#define MSG_CNG_SDCARD "Vymenit SD"
|
||||
#define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
#define MSG_BABYSTEP_Z "Doladeni osy Z"
|
||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||
#define MSG_ADJUSTZ "Auto doladit Z ?"
|
||||
#define MSG_PICK_Z "Vyberte vytisk"
|
||||
|
||||
|
@ -139,7 +73,17 @@
|
|||
#define MSG_SETTINGS "Nastaveni"
|
||||
#define MSG_PREHEAT "Predehrev"
|
||||
#define MSG_UNLOAD_FILAMENT "Vyjmout filament"
|
||||
#define MSG_LOAD_FILAMENT "Zavest filament"
|
||||
#define MSG_LOAD_FILAMENT "Zavest filament"
|
||||
#define MSG_LOAD_FILAMENT_1 "Zavest filament 1"
|
||||
#define MSG_LOAD_FILAMENT_2 "Zavest filament 2"
|
||||
#define MSG_LOAD_FILAMENT_3 "Zavest filament 3"
|
||||
#define MSG_LOAD_FILAMENT_4 "Zavest filament 4"
|
||||
#define MSG_UNLOAD_FILAMENT_1 "Vyjmout filam. 1"
|
||||
#define MSG_UNLOAD_FILAMENT_2 "Vyjmout filam. 2"
|
||||
#define MSG_UNLOAD_FILAMENT_3 "Vyjmout filam. 3"
|
||||
#define MSG_UNLOAD_FILAMENT_4 "Vyjmout filam. 4"
|
||||
#define MSG_UNLOAD_ALL "Vyjmout vse"
|
||||
#define MSG_LOAD_ALL "Zavest vse"
|
||||
|
||||
#define MSG_RECTRACT "Rectract"
|
||||
#define MSG_ERROR "CHYBA:"
|
||||
|
@ -154,32 +98,23 @@
|
|||
#define MSG_PLEASE_WAIT "Prosim cekejte"
|
||||
#define MSG_LOADING_COLOR "Cisteni barvy"
|
||||
#define MSG_CHANGE_SUCCESS "Zmena uspesna!"
|
||||
#define MSG_PRESS "A stisknete tlacitko"
|
||||
#define MSG_PRESS "a stisknete tlacitko"
|
||||
#define MSG_INSERT_FILAMENT "Vlozte filament"
|
||||
#define MSG_CHANGING_FILAMENT "Vymena filamentu!"
|
||||
|
||||
#define MSG_SILENT_MODE_ON "Mod [tichy]"
|
||||
#define MSG_SILENT_MODE_OFF "Mod [vys. vykon]"
|
||||
#define MSG_SILENT_MODE_ON "Mod [Stealth]"
|
||||
#define MSG_SILENT_MODE_OFF "Mod [Normal]"
|
||||
#define MSG_REBOOT "Restartujte tiskarnu"
|
||||
#define MSG_TAKE_EFFECT " pro projeveni zmen"
|
||||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_EXTERNAL_RESET " External Reset"
|
||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
||||
#define MSG_AUTHOR " | Author: "
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
#define MSG_FILE_PRINTED "Done printing file"
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
|
@ -194,23 +129,12 @@
|
|||
#define MSG_BED_HEATING "Zahrivani bed"
|
||||
#define MSG_BED_DONE "Bed OK."
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_COUNT_X " Count X: "
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
#define MSG_X_MIN "x_min: "
|
||||
#define MSG_X_MAX "x_max: "
|
||||
#define MSG_Y_MIN "y_min: "
|
||||
#define MSG_Y_MAX "y_max: "
|
||||
#define MSG_Z_MIN "z_min: "
|
||||
#define MSG_Z_MAX "z_max: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
|
@ -220,7 +144,6 @@
|
|||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_SIZE " Size: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
|
@ -231,14 +154,13 @@
|
|||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Dostavovani Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
|
||||
#define MSG_LANGUAGE_NAME "Cestina"
|
||||
#define MSG_LANGUAGE_SELECT "Vyber jazyka "
|
||||
#define MSG_LANGUAGE_SELECT "Vyber jazyka"
|
||||
#define MSG_PRUSA3D "prusa3d.cz"
|
||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.cz"
|
||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.cz"
|
||||
|
@ -259,6 +181,12 @@
|
|||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||
#define MSG_SELFTEST_OK "Self test OK"
|
||||
|
||||
#define MSG_SELFTEST_FAN "Test ventilatoru"
|
||||
#define MSG_SELFTEST_COOLING_FAN "Predni tiskovy vent?"
|
||||
#define MSG_SELFTEST_EXTRUDER_FAN "Levy vent na trysce?"
|
||||
#define MSG_SELFTEST_FAN_YES "Toci se"
|
||||
#define MSG_SELFTEST_FAN_NO "Netoci se"
|
||||
|
||||
#define MSG_STATS_TOTALFILAMENT "Filament celkem :"
|
||||
#define MSG_STATS_TOTALPRINTTIME "Celkovy cas :"
|
||||
#define MSG_STATS_FILAMENTUSED "Filament : "
|
||||
|
@ -278,38 +206,149 @@
|
|||
#define MSG_STATISTICS "Statistika "
|
||||
#define MSG_USB_PRINTING "Tisk z USB "
|
||||
|
||||
#define MSG_SHOW_END_STOPS "Zobraz konc. spinace"
|
||||
#define MSG_CALIBRATE_BED "Kalibrace X/Y"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset X/Y kalibr."
|
||||
#define MSG_SHOW_END_STOPS "Stav konc. spin."
|
||||
#define MSG_CALIBRATE_BED "Kalibrace XYZ"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset XYZ kalibr."
|
||||
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibrace XYZ. Otacenim tlacitka posunte Z osu az k~hornimu dorazu. Potvrdte tlacitkem."
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Kalibrace Z. Otacenim tlacitka posunte Z osu az k~hornimu dorazu. Potvrdte tlacitkem."
|
||||
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibrace X/Y. Posunte prosim Z osu az k~hornimu dorazu. Potvrdte tlacitkem."
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN "Pro uspesnou kalibraci ocistete prosim tiskovou trysku. Potvrdte tlacitkem."
|
||||
#define MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Dojely oba Z voziky k~hornimu dorazu?"
|
||||
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Hledam kalibracni"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 "bod podlozky"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE3 " z 4"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Zlepsuji presnost"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 "kalibracniho bodu"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE3 " z 9"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Hledam kalibracni bod podlozky"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Zlepsuji presnost kalibracniho bodu"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Merim referencni vysku kalibracniho bodu"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " z 9"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iterace "
|
||||
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibrace X/Y selhala. Kalibracni bod podlozky nenalezen."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibrace X/Y selhala. Nahlednete do manualu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "X/Y calibration ok. X/Y axes are perpendicular."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Kalibrace X/Y v poradku. X/Y osy mirne zkosene."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "X/Y osy jsou silne zkosene. Zkoseni bude automaticky vyrovnano pri tisku."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Kalibrace X/Y selhala. Levy predni bod moc vpredu. Srovnejte tiskarnu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Kalibrace X/Y selhala. Pravy predni bod moc vpredu. Srovnejte tiskarnu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Kalibrace X/Y selhala. Predni kalibracni body moc vpredu. Srovnejte tiskarnu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Kalibrace X/Y nepresna. Levy predni bod moc vpredu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Kalibrace X/Y nepresna. Pravy predni bod moc vpredu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Kalibrace X/Y nepresna. Predni kalibracni body moc vpredu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibrace XYZ selhala. Kalibracni bod podlozky nenalezen."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibrace XYZ selhala. Nahlednete do manualu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Kalibrace XYZ v poradku. X/Y osy jsou kolme. Gratuluji!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Kalibrace XYZ v poradku. X/Y osy mirne zkosene. Dobra prace!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Kalibrace XYZ v poradku. Zkoseni bude automaticky vyrovnano pri tisku."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Kalibrace XYZ selhala. Levy predni bod moc vpredu. Srovnejte tiskarnu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Kalibrace XYZ selhala. Pravy predni bod moc vpredu. Srovnejte tiskarnu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Kalibrace XYZ selhala. Predni kalibracni body moc vpredu. Srovnejte tiskarnu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Kalibrace XYZ nepresna. Levy predni bod moc vpredu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Kalibrace XYZ nepresna. Pravy predni bod moc vpredu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Kalibrace XYZ nepresna. Predni kalibracni body moc vpredu."
|
||||
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_LOW "Kalibrace Z selhala. Sensor nesepnul. Znecistena tryska? Cekam na reset."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_HIGH "Kalibrace Z selhala. Sensor sepnul prilis vysoko. Cekam na reset."
|
||||
#define MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Kalibrace Z selhala. Sensor je odpojeny nebo preruseny kabel. Cekam na reset."
|
||||
|
||||
#define MSG_NEW_FIRMWARE_AVAILABLE "Vysla nova verze firmware:"
|
||||
#define MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Prosim aktualizujte."
|
||||
#define MSG_BABYSTEP_Z_NOT_SET "Tiskarna nebyla jeste zkalibrovana. Spustte kalibracni G-kod a doladte Z."
|
||||
#define MSG_FOLLOW_CALIBRATION_FLOW "Tiskarna nebyla jeste zkalibrovana. Postupujte prosim podle manualu, kapitola Zaciname, odstavec Postup kalibrace."
|
||||
#define MSG_BABYSTEP_Z_NOT_SET "Neni zkalibrovana vzdalenost trysky od tiskove podlozky. Postupujte prosim podle manualu, kapitola Zaciname, odstavec Nastaveni prvni vrstvy."
|
||||
|
||||
#endif // LANGUAGE_EN_H
|
||||
#define MSG_BED_CORRECTION_MENU "Korekce podlozky"
|
||||
#define MSG_BED_CORRECTION_LEFT "Vlevo [um]"
|
||||
#define MSG_BED_CORRECTION_RIGHT "Vpravo [um]"
|
||||
#define MSG_BED_CORRECTION_FRONT "Vpredu [um]"
|
||||
#define MSG_BED_CORRECTION_REAR "Vzadu [um]"
|
||||
#define MSG_BED_CORRECTION_RESET "Reset"
|
||||
|
||||
#define MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
#define MSG_MENU_CALIBRATION "Kalibrace"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
|
||||
#define MSG_LOOSE_PULLEY "Uvolnena remenicka"
|
||||
#define MSG_FILAMENT_LOADING_T0 "Vlozte filament do extruderu 1. Potvrdte tlacitkem."
|
||||
#define MSG_FILAMENT_LOADING_T1 "Vlozte filament do extruderu 2. Potvrdte tlacitkem."
|
||||
#define MSG_FILAMENT_LOADING_T2 "Vlozte filament do extruderu 3. Potvrdte tlacitkem."
|
||||
#define MSG_FILAMENT_LOADING_T3 "Vlozte filament do extruderu 4. Potvrdte tlacitkem."
|
||||
#define MSG_CHANGE_EXTR "Zmenit extruder"
|
||||
|
||||
#define MSG_FIL_ADJUSTING "Probiha srovnani filamentu. Prosim cekejte."
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamenty jsou srovnany. Pro uspesnou kalibraci prosim ocistete trysku. Po te potvrdte tlacitkem."
|
||||
#define MSG_CALIBRATE_E "Kalibrovat E"
|
||||
#define MSG_E_CAL_KNOB "Otacejte tlacitkem dokud znacka nedosahne tela extruderu. Potvrdte tlacitkem."
|
||||
#define MSG_MARK_FIL "Oznacte filament 100 mm od tela extruderu a po te potvrdte tlacitkem."
|
||||
#define MSG_CLEAN_NOZZLE_E "E kalibrace ukoncena. Prosim ocistete trysku. Po te potvrdte tlacitkem."
|
||||
#define MSG_WAITING_TEMP "Cekani na zchladnuti trysky a podlozky."
|
||||
#define MSG_FILAMENT_CLEAN "Je barva cista?"
|
||||
#define MSG_UNLOADING_FILAMENT "Vysouvam filament"
|
||||
|
||||
#define MSG_PAPER "Umistete list papiru na podlozku a udrzujte jej pod tryskou behem mereni prvnich 4 bodu. Pokud tryska zachyti papir, vypnete tiskarnu."
|
||||
|
||||
#define MSG_FINISHING_MOVEMENTS "Dokoncovani pohybu"
|
||||
#define MSG_PRINT_PAUSED "Tisk pozastaven"
|
||||
#define MSG_RESUMING_PRINT "Obnovovani tisku"
|
||||
#define MSG_PID_EXTRUDER "PID kalibrace"
|
||||
#define MSG_SET_TEMPERATURE "Nastavte teplotu:"
|
||||
#define MSG_PID_FINISHED "PID kal. ukoncena"
|
||||
#define MSG_PID_RUNNING "PID kal. "
|
||||
|
||||
#define MSG_CALIBRATE_PINDA "Zkalibrovat"
|
||||
#define MSG_CALIBRATION_PINDA_MENU "Teplot. kalibrace"
|
||||
#define MSG_PINDA_NOT_CALIBRATED "Tiskarna nebyla teplotne zkalibrovana"
|
||||
#define MSG_PINDA_PREHEAT "Nahrivani PINDA"
|
||||
#define MSG_TEMP_CALIBRATION "Tepl. kal. "
|
||||
#define MSG_TEMP_CALIBRATION_DONE "Teplotni kalibrace dokoncena. Pokracujte stiskem tlacitka."
|
||||
#define MSG_TEMP_CALIBRATION_ON "Tepl. kal. [zap]"
|
||||
#define MSG_TEMP_CALIBRATION_OFF "Tepl. kal. [vyp]"
|
||||
#define MSG_PREPARE_FILAMENT "Pripravte filament"
|
||||
#define MSG_ALL "Vse"
|
||||
#define MSG_USED "Pouzite behem tisku"
|
||||
#define MSG_CURRENT "Pouze aktualni"
|
||||
#define MSG_CHOOSE_EXTRUDER "Vyberte extruder:"
|
||||
#define MSG_EXTRUDER "Extruder"
|
||||
#define MSG_EXTRUDER_1 "Extruder 1"
|
||||
#define MSG_EXTRUDER_2 "Extruder 2"
|
||||
#define MSG_EXTRUDER_3 "Extruder 3"
|
||||
#define MSG_EXTRUDER_4 "Extruder 4"
|
||||
|
||||
#define MSG_WIZARD "Wizard"
|
||||
#define MSG_WIZARD_WELCOME "Dobry den, jsem vase tiskarna Original Prusa i3. Chcete abych Vas provedla kalibracnim procesem?"
|
||||
#define MSG_WIZARD_QUIT "Wizarda muzete kdykoliv znovu spustit z menu Calibration -> Wizard"
|
||||
#define MSG_WIZARD_SELFTEST "Nejdriv pomoci selftestu zkontoluji nejcastejsi chyby vznikajici pri sestaveni tiskarny."
|
||||
#define MSG_WIZARD_CALIBRATION_FAILED "Prosim nahlednete do manualu a opravte problem. Po te obnovte Wizarda rebootovanim tiskarny."
|
||||
#define MSG_WIZARD_XYZ_CAL "Nyni provedu xyz kalibraci. Zabere to priblizne 12 min."
|
||||
#define MSG_WIZARD_FILAMENT_LOADED "Je filament zaveden?"
|
||||
#define MSG_WIZARD_Z_CAL "Nyni provedu z kalibraci."
|
||||
#define MSG_WIZARD_WILL_PREHEAT "Nyni predehreji trysku pro PLA."
|
||||
#define MSG_WIZARD_V2_CAL "Nyni zkalibruji vzdalenost mezi koncem trysky a povrchem heatbedu."
|
||||
#define MSG_WIZARD_V2_CAL_2 "Zacnu tisknout linku a Vy budete postupne snizovat trysku otacenim tlacitka dokud nedosahnete optimalni vysky. Prohlednete si obrazky v nasi prirucce v kapitole Kalibrace"
|
||||
#define MSG_V2_CALIBRATION "Kal. prvni vrstvy"
|
||||
#define MSG_WIZARD_DONE "Vse je hotovo."
|
||||
#define MSG_WIZARD_LOAD_FILAMENT "Prosim vlozte PLA filament do extruderu, po te stisknete tlacitko pro zavedeni filamentu."
|
||||
#define MSG_WIZARD_RERUN "Spusteni Wizarda vymaze ulozene vysledky vsech kalibraci a spusti kalibracni proces od zacatku. Pokracovat?"
|
||||
#define MSG_WIZARD_REPEAT_V2_CAL "Chcete opakovat posledni krok a pozmenit vzdalenost mezi tryskou a heatbed?"
|
||||
#define MSG_WIZARD_CLEAN_HEATBED "Prosim ocistete heatbed a stisknete tlacitko."
|
||||
#define MSG_WIZARD_PLA_FILAMENT "Je to PLA filament?"
|
||||
#define MSG_WIZARD_INSERT_CORRECT_FILAMENT "Prosim zavedte PLA filament a po te obnovte Wizarda stisknutim reset tlacitka."
|
||||
#define MSG_PLA_FILAMENT_LOADED "Je PLA filament zaveden?"
|
||||
#define MSG_PLEASE_LOAD_PLA "Nejdrive zavedte PLA filament prosim."
|
||||
#define MSG_WIZARD_HEATING "Predehrivam trysku. Prosim cekejte."
|
||||
#define MSG_M117_V2_CALIBRATION "M117 Kal. prvni vrstvy"
|
||||
|
||||
#define MSG_DATE "Datum:"
|
||||
#define MSG_XYZ_DETAILS "Detaily XYZ kal."
|
||||
#define MSG_Y_DISTANCE_FROM_MIN "Y vzdalenost od min:"
|
||||
#define MSG_LEFT "Levy:"
|
||||
#define MSG_RIGHT "Pravy:"
|
||||
#define MSG_MEASURED_SKEW "Merene zkoseni:"
|
||||
#define MSG_SLIGHT_SKEW "Lehke zkoseni:"
|
||||
#define MSG_SEVERE_SKEW "Tezke zkoseni:"
|
||||
|
||||
#define MSG_CALIBRATE_Z_AUTO "Kalibruji Z"
|
||||
#define MSG_FSENSOR_OFF "Fil. senzor [vyp]"
|
||||
#define MSG_FSENSOR_ON "Fil. senzor [zap]"
|
||||
#define MSG_CRASHDETECT_ON "Crash det. [zap]"
|
||||
#define MSG_CRASHDETECT_OFF "Crash det. [vyp]"
|
||||
#define MSG_FANS_CHECK_ON "Kontr. vent.[zap]"
|
||||
#define MSG_FANS_CHECK_OFF "Kontr. vent.[vyp]"
|
||||
#define MSG_RECOVERING_PRINT "Obnovovani tisku "
|
||||
#define MSG_SELFTEST_AXIS "Osa"
|
||||
#define MSG_SELFTEST_AXIS_LENGTH "Delka osy"
|
||||
#define MSG_STEEL_SHEET_CHECK "Je tiskovy plat na heatbed?"
|
||||
#define MSG_REMOVE_STEEL_SHEET "Odstrante tiskovy plat z heatbed prosim."
|
||||
#define MSG_PLACE_STEEL_SHEET "Umistete prosim tiskovy plat na heatbed"
|
||||
#define MSG_RECOVER_PRINT "Detekovan vypadek proudu.Obnovit tisk?"
|
||||
#define MSG_PRESS_TO_UNLOAD "Pro vysunuti filamentu stisknete prosim tlacitko"
|
||||
#define MSG_UNLOAD_SUCCESSFULL "Opakovat vysunuti filamentu?"
|
350
Firmware/language_de.h
Normal file
350
Firmware/language_de.h
Normal file
|
@ -0,0 +1,350 @@
|
|||
+/**
|
||||
+ * German
|
||||
+ *
|
||||
+ * LCD Menu Messages
|
||||
+ * Please note these are limited to 17 characters!
|
||||
+ *
|
||||
+ */
|
||||
+
|
||||
+#define(length = 20) WELCOME_MSG CUSTOM_MENDEL_NAME " bereit."
|
||||
+ #define MSG_SD_INSERTED "SD eingesetzt"
|
||||
+ #define MSG_SD_REMOVED "SD entfernt "
|
||||
+ #define MSG_MAIN "Hauptmenue"
|
||||
+ #define MSG_DISABLE_STEPPERS "Motoren aus"
|
||||
+ #define MSG_AUTO_HOME "Startposition"
|
||||
+ #define MSG_SET_HOME_OFFSETS "Abstand vom Ursprung einstellen"
|
||||
+ #define MSG_SET_ORIGIN "Ursprung einstellen"
|
||||
+ #define MSG_COOLDOWN "Abkuehlen"
|
||||
+ #define MSG_SWITCH_PS_ON "Netzteil EIN"
|
||||
+ #define MSG_SWITCH_PS_OFF "Netzteil AUS"
|
||||
+ #define MSG_MOVE_AXIS "Achsbewegung"
|
||||
+ #define MSG_MOVE_X "Bewege X"
|
||||
+ #define MSG_MOVE_Y "Bewege Y"
|
||||
+ #define MSG_MOVE_Z "Bewege Z"
|
||||
+ #define MSG_MOVE_E "Extruder"
|
||||
+ #define MSG_SPEED "Geschwindigkeit"
|
||||
+ #define MSG_NOZZLE "Duese"
|
||||
+ #define MSG_NOZZLE1 "Duese2"
|
||||
+ #define MSG_NOZZLE2 "Duese3"
|
||||
+ #define MSG_BED "Bett"
|
||||
+ #define MSG_FAN_SPEED "Luefter-Tempo"
|
||||
+ #define MSG_FLOW "Durchfluss"
|
||||
+ #define MSG_FLOW0 "Durchfluss 0"
|
||||
+ #define MSG_FLOW1 "Durchfluss 1"
|
||||
+ #define MSG_FLOW2 "Durchfluss 2"
|
||||
+ #define MSG_CONTROL "Kontrolle"
|
||||
+ #define MSG_MIN " \002 Min"
|
||||
+ #define MSG_MAX " \002 Max"
|
||||
+ #define MSG_FACTOR " \002 Fakt"
|
||||
+ #define MSG_TEMPERATURE "Temperatur"
|
||||
+ #define MSG_MOTION "Bewegung"
|
||||
+ #define MSG_VOLUMETRIC "Filament"
|
||||
+ #define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
+ #define MSG_STORE_EPROM "Abspeichern"
|
||||
+ #define MSG_LOAD_EPROM "Lade Speicher"
|
||||
+ #define MSG_RESTORE_FAILSAFE "Standardwerte setzen"
|
||||
+ #define MSG_REFRESH "\xF8" "Erneuern"
|
||||
+ #define MSG_WATCH "Information"
|
||||
+ #define MSG_TUNE "Feineinstellung"
|
||||
+ #define MSG_PAUSE_PRINT "Druck unterbrech."
|
||||
+ #define MSG_RESUME_PRINT "Fortsetzen"
|
||||
+ #define MSG_STOP_PRINT "Druck abbrechen"
|
||||
+ #define MSG_CARD_MENU "Drucken von SD"
|
||||
+ #define MSG_NO_CARD "Keine SD Karte"
|
||||
+ #define MSG_DWELL "Einen Moment bitte."
|
||||
+ #define MSG_USERWAIT "Warte auf user..."
|
||||
+ #define MSG_RESUMING "Druck fortgesetzt"
|
||||
+ #define(length = 20) MSG_PRINT_ABORTED "Druck abgebrochen"
|
||||
+ #define MSG_NO_MOVE "Keine Bewegung."
|
||||
+ #define MSG_KILLED "ABGEBROCHEN. "
|
||||
+ #define MSG_STOPPED "GESTOPPT. "
|
||||
+ #define MSG_FILAMENTCHANGE "Filament-Wechsel"
|
||||
+ #define MSG_INIT_SDCARD "Init SD Karte"
|
||||
+ #define MSG_CNG_SDCARD "Wechsel SD Karte"
|
||||
+ #define MSG_BABYSTEP_X "Babystep X"
|
||||
+ #define MSG_BABYSTEP_Y "Babystep Y"
|
||||
+ #define MSG_BABYSTEP_Z "Z einstellen"
|
||||
+ #define MSG_ADJUSTZ "Auto Z einstellen?"
|
||||
+ #define MSG_PICK_Z "Waehle Abdruck"
|
||||
+
|
||||
+#define MSG_SETTINGS "Einstellungen"
|
||||
+ #define MSG_PREHEAT "Vorwaermen"
|
||||
+ #define MSG_UNLOAD_FILAMENT "Filament entladen"
|
||||
+ #define MSG_LOAD_FILAMENT "Filament laden"
|
||||
+
|
||||
+#define MSG_RECTRACT "Retract"
|
||||
+ #define MSG_ERROR "FEHLER:"
|
||||
+ #define(length = 20) MSG_PREHEAT_NOZZLE "Duese Vorwaermen"
|
||||
+ #define MSG_SUPPORT "Support"
|
||||
+ #define(length = 20) MSG_CORRECTLY "Wechsel ok?"
|
||||
+ #define MSG_YES "Ja"
|
||||
+ #define MSG_NO "Nein"
|
||||
+ #define(length = 19) MSG_NOT_LOADED "Fil. nicht geladen"
|
||||
+ #define MSG_NOT_COLOR "Farbe unklar"
|
||||
+ #define(length = 20) MSG_LOADING_FILAMENT "Filament leadt"
|
||||
+ #define(length = 20) MSG_PLEASE_WAIT "Bitte warten"
|
||||
+ #define MSG_LOADING_COLOR "Lade Farbe"
|
||||
+ #define MSG_CHANGE_SUCCESS "Wechsel erfolgr.!"
|
||||
+ #define(length = 20) MSG_PRESS "und Knopf druecken"
|
||||
+ #define(length = 20) MSG_INSERT_FILAMENT "Filament einlegen"
|
||||
+ #define(length = 20) MSG_CHANGING_FILAMENT "Filament-Wechsel!"
|
||||
+
|
||||
+
|
||||
+#define MSG_SILENT_MODE_ON "Mode [leise]"
|
||||
+ #define MSG_SILENT_MODE_OFF "Mode [Hohe Leist]"
|
||||
+ #define(length = 20) MSG_REBOOT "Zum Uebernehmen "
|
||||
+ #define(length = 22) MSG_TAKE_EFFECT "Drucker neu starten"
|
||||
+
|
||||
+#define MSG_Enqueing "enqueuing \"
|
||||
+ #define MSG_POWERUP "Einschalten"
|
||||
+ #define MSG_CONFIGURATION_VER " Letztes Update:"
|
||||
+ #define MSG_FREE_MEMORY " Freier Speicher: "
|
||||
+ #define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
+ #define MSG_OK "ok"
|
||||
+ #define MSG_ERR_CHECKSUM_MISMATCH "Pruefsummenfehler, Letzte Zeile: " //Checksum Fehler, Letzte Zeile: "
|
||||
+ #define MSG_ERR_NO_CHECKSUM "Keine Pruefsumme mit Zeilennummer, Letzte Zeile: " //Keine Checksum mit Zeilennummer, Letzte Zeile: "
|
||||
+ #define MSG_BEGIN_FILE_LIST "Beginn Dateiliste"
|
||||
+ #define MSG_END_FILE_LIST "Ende Dateiliste"
|
||||
+ #define MSG_M104_INVALID_EXTRUDER "M104 Falscher Extruder"
|
||||
+ #define MSG_M105_INVALID_EXTRUDER "M105 Falscher Extruder"
|
||||
+ #define MSG_M200_INVALID_EXTRUDER "M200 Falscher Extruder"
|
||||
+ #define MSG_M218_INVALID_EXTRUDER "M218 Falscher Extruder"
|
||||
+ #define MSG_M221_INVALID_EXTRUDER "M221 Falscher Extruder"
|
||||
+ #define MSG_ERR_NO_THERMISTORS "Keine Thermistoren - keine Temperatur"
|
||||
+ #define MSG_M109_INVALID_EXTRUDER "M109 Falscher Extruder"
|
||||
+ #define MSG_HEATING "Aufwaermen"
|
||||
+ #define(length = 20) MSG_HEATING_COMPLETE "Aufwaermen OK"
|
||||
+ #define MSG_BED_HEATING "Bett aufwaermen"
|
||||
+ #define MSG_BED_DONE "Bett OK"
|
||||
+ #define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
+ #define MSG_ERR_KILLED "Printer gestoppt. kill() aufgerufen!"
|
||||
+ #define MSG_ERR_STOPPED "Drucker aufgrund von Fehlern gestoppt. Fehler beheben und mit M999 neu starten. (Temperatur wird zurueckgesetzt. Nach dem Neustart neu einstellen!)"
|
||||
+ #define MSG_RESEND "Wiederholen: "
|
||||
+ #define MSG_M119_REPORT "Statusbericht Endanschlag"
|
||||
+ #define MSG_ENDSTOP_HIT "AUSGELOEST"
|
||||
+ #define MSG_ENDSTOP_OPEN "offen"
|
||||
+
|
||||
+#define MSG_SD_CANT_OPEN_SUBDIR "Kann Unterverz. nicht oeffnen"
|
||||
+ #define MSG_SD_INIT_FAIL "SD Init fehlerhaft"
|
||||
+ #define MSG_SD_VOL_INIT_FAIL "Dateisystem Init fehlerhaft"
|
||||
+ #define MSG_SD_OPENROOT_FAIL "Zugriff auf Basisverzeichnis misslungen"
|
||||
+ #define MSG_SD_CARD_OK "SD Karte ok"
|
||||
+ #define MSG_SD_WORKDIR_FAIL "Oeffnen Arbeitsverzeichnis misslungen"
|
||||
+ #define MSG_SD_OPEN_FILE_FAIL "Fehler beim Oeffnen der Datei: "
|
||||
+ #define MSG_SD_FILE_OPENED "Datei geoeffnet: "
|
||||
+ #define MSG_SD_FILE_SELECTED "Datei ausgewaehlt"
|
||||
+ #define MSG_SD_WRITE_TO_FILE "Schreiben der Datei: "
|
||||
+ #define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
+ #define MSG_SD_NOT_PRINTING "Kein SD Print"
|
||||
+ #define MSG_SD_ERR_WRITE_TO_FILE "Fehler beim Schreiben in Datei"
|
||||
+ #define MSG_SD_CANT_ENTER_SUBDIR "Zugangsproblem Unterverzeichnis: "
|
||||
+ #define MSG_STEPPER_TOO_HIGH "Schrittrate zu hoch"
|
||||
+ #define MSG_ENDSTOPS_HIT "Endanschlag erreicht"
|
||||
+ #define MSG_ERR_COLD_EXTRUDE_STOP "Stopp, Extruder kalt!"
|
||||
+ #define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
+ #define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
+ #define MSG_BABYSTEPPING_Z "Z wurde eingestellt"
|
||||
+ #define MSG_SERIAL_ERROR_MENU_STRUCTURE "Menuestruktur fehlerhaft"
|
||||
+
|
||||
+#define MSG_LANGUAGE_NAME "Deutsch"
|
||||
+ #define MSG_LANGUAGE_SELECT "Waehle Sprache"
|
||||
+ #define MSG_PRUSA3D "prusa3d.com"
|
||||
+ #define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
+ #define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
+
|
||||
+#define MSG_SELFTEST_ERROR "Selbtest Fehler!"
|
||||
+ #define MSG_SELFTEST_PLEASECHECK "Bitte pruefe:"
|
||||
+ #define MSG_SELFTEST_NOTCONNECTED "Nicht angeschlossen"
|
||||
+ #define MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
|
||||
+ #define MSG_SELFTEST_BEDHEATER "Bett / Heater"
|
||||
+ #define MSG_SELFTEST_WIRINGERROR "Verdrahtungfehler"
|
||||
+ #define MSG_SELFTEST_ENDSTOPS "Endschalter"
|
||||
+ #define MSG_SELFTEST_MOTOR "Motor"
|
||||
+ #define MSG_SELFTEST_ENDSTOP "Endstop"
|
||||
+ #define MSG_SELFTEST_ENDSTOP_NOTHIT "Ende nicht getrof."
|
||||
+ #define MSG_SELFTEST_OK "Selbsttest OK"
|
||||
+ #define MSG_LOOSE_PULLEY "Lose Riemenscheibe"
|
||||
+
|
||||
+#define MSG_SELFTEST_FAN "Lueftertest"
|
||||
+#define(length = 20) MSG_SELFTEST_COOLING_FAN "Vorderer Luefter?"
|
||||
+#define(length = 20) MSG_SELFTEST_EXTRUDER_FAN "Linker Luefter?"
|
||||
+#define MSG_SELFTEST_FAN_YES "Dreht"
|
||||
+#define MSG_SELFTEST_FAN_NO "Dreht nicht"
|
||||
+
|
||||
+#define(length = 20) MSG_STATS_TOTALFILAMENT "Gesamtfilament:"
|
||||
+ #define(length = 20) MSG_STATS_TOTALPRINTTIME "Totale Druckzeit:"
|
||||
+ #define(length = 20) MSG_STATS_FILAMENTUSED "Filamentverbrauch:"
|
||||
+ #define(length = 20) MSG_STATS_PRINTTIME "Druckzeit: "
|
||||
+ #define(length = 20) MSG_SELFTEST_START "Selbsttest start "
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_ENDSTOPS "Pruefe Endschalter "
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_HOTEND "Pruefe Duese"
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_X "Pruefe X Achse "
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_Y "Pruefe Y Achse "
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_Z "Pruefe Z Achse "
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_BED "Pruefe Bett "
|
||||
+ #define(length = 20) MSG_SELFTEST_CHECK_ALLCORRECT "Alles richtig "
|
||||
+ #define MSG_SELFTEST "Selbsttest "
|
||||
+ #define(length = 20) MSG_SELFTEST_FAILED "Selbsttest misslung."
|
||||
+ #define MSG_STATISTICS "Statistiken "
|
||||
+ #define MSG_USB_PRINTING "Drucken ueber USB"
|
||||
+ #define MSG_HOMEYZ "Kalibrieren Z"
|
||||
+ #define MSG_HOMEYZ_PROGRESS "Kalibriere Z"
|
||||
+ #define MSG_HOMEYZ_DONE "Kalibrierung OK"
|
||||
+
|
||||
+#define MSG_SHOW_END_STOPS "Endschalter Stat."
|
||||
+ #define MSG_CALIBRATE_BED "Kalibrierung XYZ"
|
||||
+ #define MSG_CALIBRATE_BED_RESET "Reset XYZ Kalibr."
|
||||
+
|
||||
|
||||
+#define(length = 20, lines = 8) MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibrieren von XYZ. Drehen Sie den Knopf bis der obere Anschlag erreicht wird. Klicken Sie den Knopf wenn es ganz oben wird."
|
||||
+ #define(length = 20, lines = 8) MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Kalibrieren von Z. Drehen Sie den Knopf bis der obere Anschlag erreicht wird. Klicken Sie den Knopf wenn es ganz oben wird."
|
||||
+
|
||||
|
||||
+#define(length = 20, lines = 8) MSG_CONFIRM_NOZZLE_CLEAN "Bitte entfernen Sie ueberstehendes Filament von der Duese. Klicken wenn sauber."
|
||||
+ #define(length = 20, lines = 2) MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Ist der Schlitten ganz oben?"
|
||||
+
|
||||
+#define(length = 60) MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Suchen Bett Kalibrierpunkt"
|
||||
+ #define(length = 14) MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " von 4"
|
||||
+ #define(length = 60) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Verbesserung Bett Kalibrierpunkt"
|
||||
+ #define(length = 14) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " von 4"
|
||||
+ #define(length = 60) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Messen der Referenzhoehe des Kalibrierpunktes"
|
||||
+ #define(length = 14) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " von 9"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteration "
|
||||
+
|
||||
+#define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "XYZ-Kalibrierung fehlgeschlagen. Bett-Kalibrierpunkt nicht gefunden."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "XYZ-Kalibrierung fehlgeschlagen. Bitte schauen Sie in das Handbuch."
|
||||
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "XYZ-Kalibrierung ok. X/Y-Achsen sind senkrecht zueinander. Glueckwunsch!"
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "XYZ Kalibrierung in Ordnung. X/Y Achsen sind etwas schief."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "XYZ Kalibrierung in Ordnung. Schiefheit wird automatisch korrigiert."
|
||||
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "XYZ-Kalibrierung fehlgeschlagen. Linker vorderer Kalibrierpunkt ist zu weit vorne."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "XYZ-Kalibrierung fehlgeschlagen. Rechter vorderer Kalibrierpunkt ist zu weit vorne."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "XYZ-Kalibrierung fehlgeschlagen. Vordere Kalibrierpunkte sind zu weit vorne."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "XYZ-Kalibrierung ungenau. Linker vorderer Kalibrierpunkt ist zu weit vorne."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "XYZ-Kalibrierung ungenau. Rechter vorderer Kalibrierpunkt ist zu weit vorne."
|
||||
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "XYZ-Kalibrierung ungenau. Vordere Kalibrierpunkte sind zu weit vorne."
|
||||
+
|
||||
+#define(length = 20, lines = 4) MSG_BED_LEVELING_FAILED_POINT_LOW "Z-Kal. fehlgeschlg. Sensor nicht ausgeloest. Schmutzige Duese? Warte auf Reset"
|
||||
|
||||
+ #define(length = 20, lines = 4) MSG_BED_LEVELING_FAILED_POINT_HIGH "Z-Kalibrierung fehlgeschlg. Sensor zu hoch ausgeloest. Warte auf Reset."
|
||||
+ #define(length = 20, lines = 4) MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Z-Kalibrierung fehlgeschlg. Sensor nicht angeschlossen. Warte auf Reset."
|
||||
+
|
||||
+#define(length = 20, lines = 2) MSG_NEW_FIRMWARE_AVAILABLE "Neue Firmware Version verfuegbar:"
|
||||
+ #define(length = 20) MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Bitte aktualisieren."
|
||||
+
|
||||
+ #define(length = 20, lines = 8) MSG_FOLLOW_CALIBRATION_FLOW "Der Drucker wurde noch nicht kalibriert. Bitte folgen Sie das Handbuch, Kapitel First steps, Abschnitt Calibration flow."
|
||||
+ #define(length = 20, lines = 12) MSG_BABYSTEP_Z_NOT_SET "Der Abstand zwischen der Spitze der Duese und der Bett ist noch nicht eingestellt. Bitte folgen Sie dem Handbuch, First steps, section First layer calibration."
|
||||
+
|
||||
+
|
||||
|
||||
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T0 "Filament in extruder 1 einlegen. Klicken wenn fertig."
|
||||
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T1 "Filament in extruder 2 einlegen. Klicken wenn fertig."
|
||||
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T2 "Filament in extruder 3 einlegen. Klicken wenn fertig."
|
||||
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T3 "Filament in extruder 4 einlegen. Klicken wenn fertig."
|
||||
+ #define(length = 20, lines = 1) MSG_CHANGE_EXTR "Wechsel extruder"
|
||||
+
|
||||
|
||||
|
||||
+ #define(length = 20, lines = 4) MSG_FIL_ADJUSTING "Filament positionieren. Bitte warten."
|
||||
+ #define(length = 20, lines = 8) MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamente sind jetzt eingestellt. Bitte reinigen Sie die Duese zur Kalibrierung. Klicken wenn fertig."
|
||||
+
|
||||
+ #define(length = 20, lines = 1) MSG_CALIBRATE_E "Kalibriere E"
|
||||
+//#define(length=20, lines=1) "Reset E Cal."
|
||||
|
||||
+#define(length = 20, lines = 8) MSG_E_CAL_KNOB "Knopf drehen bis die Filamentmarkierung erreicht ist. Klicken wenn fertig."
|
||||
+
|
||||
+//#define(length=20, lines=1) MSG_FARM_CARD_MENU "Farm mode print"
|
||||
|
||||
+#define(length = 20, lines = 8) MSG_MARK_FIL "Filament 100mm vom Extrudergehaeuse markieren. Klicken wenn Fertig."
|
||||
+ #define(length = 20, lines = 8) MSG_CLEAN_NOZZLE_E "E-Kalibrierung beendet. Bitte reinigen Sie die Duese. Klicken wenn fertig."
|
||||
+ #define(length = 20, lines = 3) MSG_WAITING_TEMP "Warten auf Abkuehlung von Heater und Bett."
|
||||
|
||||
+ #define(length = 20, lines = 2) MSG_FILAMENT_CLEAN "Ist Farbe rein?"
|
||||
+ #define(lenght = 20, lines = 1) MSG_UNLOADING_FILAMENT "Filament auswerfen"
|
||||
+ #define(length = 20, lines = 8) MSG_PAPER "Legen ein Blatt Papier unter die Duese waehrend der Kalibrierung der ersten 4 Punkte. Wenn die Duese das Papier einklemmt, Drucker sofort ausschalten"
|
||||
+
|
||||
+#define MSG_BED_CORRECTION_MENU "Bett level Korrekt"
|
||||
|
||||
+ #define MSG_BED_CORRECTION_LEFT "Links [um]"
|
||||
+ #define MSG_BED_CORRECTION_RIGHT "Rechts [um]"
|
||||
+ #define MSG_BED_CORRECTION_FRONT "Vorne [um]"
|
||||
+ #define MSG_BED_CORRECTION_REAR "Hinten [um]"
|
||||
+ #define MSG_BED_CORRECTION_RESET "Ruecksetzen"
|
||||
+
|
||||
+#define MSG_MESH_BED_LEVELING "Mesh Bett Leveling"
|
||||
+ #define MSG_MENU_CALIBRATION "Kalibrierung"
|
||||
|
||||
+ #define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD Karte [normal]"
|
||||
+ #define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD Karte [FlashAir]"
|
||||
|
||||
#define MSG_FINISHING_MOVEMENTS "Bewegung beenden"
|
||||
#define MSG_PRINT_PAUSED "Druck pausiert"
|
||||
#define MSG_RESUMING_PRINT "Druck weitergehen"
|
||||
#define MSG_PID_EXTRUDER "PID Kalibrierung"
|
||||
#define MSG_SET_TEMPERATURE "Temp. einsetzen"
|
||||
#define MSG_PID_FINISHED "PID Kalib. fertig"
|
||||
#define MSG_PID_RUNNING "PID Kalib."
|
||||
|
||||
#define MSG_CALIBRATE_PINDA "Kalibrieren"
|
||||
#define MSG_CALIBRATION_PINDA_MENU "Temp. kalibrieren"
|
||||
#define MSG_PINDA_NOT_CALIBRATED "Temperatur wurde nicht kalibriert"
|
||||
#define MSG_PINDA_PREHEAT "PINDA erwaermen"
|
||||
#define MSG_TEMP_CALIBRATION "Temp Kalib. "
|
||||
#define MSG_TEMP_CALIBRATION_DONE "Temp. Kalibrierung fertig. Klicken um weiter zu gehen."
|
||||
#define MSG_TEMP_CALIBRATION_ON "Temp. Kal. [ON]"
|
||||
#define MSG_TEMP_CALIBRATION_OFF "Temp. Kal. [OFF]"
|
||||
|
||||
#define MSG_LOAD_ALL "Alle laden"
|
||||
#define MSG_LOAD_FILAMENT_1 "Filament 1 laden"
|
||||
#define MSG_LOAD_FILAMENT_2 "Filament 2 laden"
|
||||
#define MSG_LOAD_FILAMENT_3 "Filament 3 laden"
|
||||
#define MSG_LOAD_FILAMENT_4 "Filament 4 laden"
|
||||
#define MSG_UNLOAD_FILAMENT_1 "Filam. 1 entladen"
|
||||
#define MSG_UNLOAD_FILAMENT_2 "Filam. 2 entladen"
|
||||
#define MSG_UNLOAD_FILAMENT_3 "Filam. 3 entladen"
|
||||
#define MSG_UNLOAD_FILAMENT_4 "Filam. 4 entladen"
|
||||
#define MSG_UNLOAD_ALL "Alles entladen"
|
||||
#define MSG_PREPARE_FILAMENT "Filam. bereithalten"
|
||||
#define MSG_ALL "Alle"
|
||||
#define MSG_USED "Beim Druck benutzte"
|
||||
#define MSG_CURRENT "Aktuelles"
|
||||
#define MSG_CHOOSE_EXTRUDER "Waehlen Sie Extruder"
|
||||
#define MSG_EXTRUDER "Extruder"
|
||||
#define MSG_EXTRUDER_1 "Extruder 1"
|
||||
#define MSG_EXTRUDER_2 "Extruder 2"
|
||||
#define MSG_EXTRUDER_3 "Extruder 3"
|
||||
#define MSG_EXTRUDER_4 "Extruder 4"
|
||||
|
||||
#define MSG_WIZARD "Wizard"
|
||||
#define MSG_WIZARD_WELCOME "Hallo, ich bin dein Original Prusa i3 Drucker. Moechten Sie meine Hilfe durch den Setup-Prozess?"
|
||||
#define MSG_WIZARD_QUIT "Sie koennen immer den Asistenten im Menu neu aufrufen: Kalibrierung -> Assistant"
|
||||
#define MSG_WIZARD_SELFTEST "Zunaechst fuehre ich den Selbsttest durch um die haeufigsten Probleme bei der Aufbau zu ueberpruefen."
|
||||
#define MSG_WIZARD_CALIBRATION_FAILED "Bitte ueberpruefen Sie unser Handbuch und beheben Sie das Problem. Fahren Sie dann mit dem Assistenten fort, indem Sie den Drucker neu starten."
|
||||
#define MSG_WIZARD_XYZ_CAL "Ich werde jetzt die XYZ-Kalibrierung durchfuehren. Es wird ca. 12 Minuten dauern"
|
||||
#define MSG_WIZARD_FILAMENT_LOADED "Ist das Filament geladen?"
|
||||
#define MSG_WIZARD_Z_CAL "Ich werde jetzt die Z Kalibrierung durchfuehren."
|
||||
#define MSG_WIZARD_WILL_PREHEAT "Jetzt werde ich die Duese fuer PLA vorheizen. "
|
||||
#define MSG_WIZARD_V2_CAL "Jetzt werde ich den Abstand zwischen Duesenspitze und Druckbett kalibrieren."
|
||||
#define MSG_WIZARD_V2_CAL_2 "Ich werde jetzt erste Linie drucken. Waehrend des Druckes koennen Sie die Duese allmaehlich senken indem Sie den Knopf drehen, bis Sie die optimale Hoehe erreichen. Ueberpruefen Sie die Bilder in unserem Handbuch im Kapitel Kalibrierung"
|
||||
#define MSG_V2_CALIBRATION "Erste-Schicht Kal"
|
||||
#define MSG_WIZARD_DONE "Alles wurde getan. Viel Spass beim Drucken!"
|
||||
#define MSG_WIZARD_LOAD_FILAMENT "Fuehren Sie bitte PLA Filament in den Extruder und bestaetigen Sie den Knopf um es zu laden."
|
||||
#define MSG_WIZARD_RERUN "Der laufende Assistent loescht die aktuelle Kalibrierergebnisse und wird von Anfang an beginnen. Fortsetzen?"
|
||||
#define MSG_WIZARD_REPEAT_V2_CAL "Moechten Sie den letzten Schritt wiederholen um den Abstand zwischen Duese und Druckbett neu einzustellen?"
|
||||
#define MSG_WIZARD_CLEAN_HEATBED "Bitte reinigen Sie das Heizbett und druecken Sie dann den Knopf."
|
||||
#define MSG_WIZARD_PLA_FILAMENT "Ist es wirklich PLA Filament?"
|
||||
#define MSG_WIZARD_INSERT_CORRECT_FILAMENT "Bitte laden Sie PLA-Filament und fahren Sie mit dem Assistenten fort, indem Sie den Drucker neu starten."
|
||||
#define MSG_PLA_FILAMENT_LOADED "Ist PLA Filament geladen?"
|
||||
#define MSG_PLEASE_LOAD_PLA "Bitte laden Sie zuerst PLA Filament."
|
||||
#define MSG_WIZARD_HEATING "Vorheizen der Duese. Bitte warten."
|
||||
#define MSG_M117_V2_CALIBRATION "M117 Erste-Schicht Kal."
|
||||
|
||||
#define MSG_DATE "Datum"
|
||||
#define MSG_XYZ_DETAILS "XYZ Kal. Details"
|
||||
#define MSG_Y_DISTANCE_FROM_MIN "Y Entfernung vom min"
|
||||
#define MSG_LEFT "Links:"
|
||||
#define MSG_RIGHT "Rechts:"
|
||||
#define MSG_MEASURED_SKEW "Schraeglauf:"
|
||||
#define MSG_SLIGHT_SKEW "Leichter Schr.:"
|
||||
#define MSG_SEVERE_SKEW "Schwerer Schr.:"
|
|
@ -5,53 +5,29 @@
|
|||
* Please note these are limited to 17 characters!
|
||||
*
|
||||
*/
|
||||
#ifndef LANGUAGE_EN_H
|
||||
#define LANGUAGE_EN_H
|
||||
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " ready."
|
||||
#define(length=20) WELCOME_MSG CUSTOM_MENDEL_NAME " ready."
|
||||
#define MSG_SD_INSERTED "Card inserted"
|
||||
#define MSG_SD_REMOVED "Card removed"
|
||||
#define MSG_MAIN "Main"
|
||||
#define MSG_AUTOSTART "Autostart"
|
||||
#define MSG_DISABLE_STEPPERS "Disable steppers"
|
||||
#define MSG_AUTO_HOME "Auto home"
|
||||
#define MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
#define MSG_SET_ORIGIN "Set origin"
|
||||
#define MSG_PREHEAT_PLA "Preheat PLA"
|
||||
#define MSG_PREHEAT_PLA0 "Preheat PLA 1"
|
||||
#define MSG_PREHEAT_PLA1 "Preheat PLA 2"
|
||||
#define MSG_PREHEAT_PLA2 "Preheat PLA 3"
|
||||
#define MSG_PREHEAT_PLA012 "Preheat PLA All"
|
||||
#define MSG_PREHEAT_PLA_BEDONLY "Preheat PLA Bed"
|
||||
#define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA conf"
|
||||
#define MSG_PREHEAT_ABS "Preheat ABS"
|
||||
#define MSG_PREHEAT_ABS0 "Preheat ABS 1"
|
||||
#define MSG_PREHEAT_ABS1 "Preheat ABS 2"
|
||||
#define MSG_PREHEAT_ABS2 "Preheat ABS 3"
|
||||
#define MSG_PREHEAT_ABS012 "Preheat ABS All"
|
||||
#define MSG_PREHEAT_ABS_BEDONLY "Preheat ABS Bed"
|
||||
#define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS conf"
|
||||
#define MSG_COOLDOWN "Cooldown"
|
||||
#define MSG_SWITCH_PS_ON "Switch power on"
|
||||
#define MSG_SWITCH_PS_OFF "Switch power off"
|
||||
#define MSG_EXTRUDE "Extrude"
|
||||
#define MSG_RETRACT "Retract"
|
||||
#define MSG_MOVE_AXIS "Move axis"
|
||||
#define MSG_MOVE_X "Move X"
|
||||
#define MSG_MOVE_Y "Move Y"
|
||||
#define MSG_MOVE_Z "Move Z"
|
||||
#define MSG_MOVE_E "Extruder"
|
||||
#define MSG_MOVE_E1 "Extruder2"
|
||||
#define MSG_MOVE_E2 "Extruder3"
|
||||
#define MSG_MOVE_01MM "Move 0.1mm"
|
||||
#define MSG_MOVE_1MM "Move 1mm"
|
||||
#define MSG_MOVE_10MM "Move 10mm"
|
||||
#define MSG_SPEED "Speed"
|
||||
#define MSG_NOZZLE "Nozzle"
|
||||
#define MSG_NOZZLE1 "Nozzle2"
|
||||
#define MSG_NOZZLE2 "Nozzle3"
|
||||
#define MSG_BED "Bed"
|
||||
#define MSG_FAN_SPEED "Fan speed"
|
||||
#define(length=14) MSG_FAN_SPEED "Fan speed"
|
||||
#define MSG_FLOW "Flow"
|
||||
#define MSG_FLOW0 "Flow 0"
|
||||
#define MSG_FLOW1 "Flow 1"
|
||||
|
@ -60,44 +36,15 @@
|
|||
#define MSG_MIN " \002 Min"
|
||||
#define MSG_MAX " \002 Max"
|
||||
#define MSG_FACTOR " \002 Fact"
|
||||
#define MSG_AUTOTEMP "Autotemp"
|
||||
#define MSG_ON "On "
|
||||
#define MSG_OFF "Off"
|
||||
#define MSG_PID_P "PID-P"
|
||||
#define MSG_PID_I "PID-I"
|
||||
#define MSG_PID_D "PID-D"
|
||||
#define MSG_PID_C "PID-C"
|
||||
#define MSG_ACC "Accel"
|
||||
#define MSG_VXY_JERK "Vxy-jerk"
|
||||
#define MSG_VZ_JERK "Vz-jerk"
|
||||
#define MSG_VE_JERK "Ve-jerk"
|
||||
#define MSG_VMAX "Vmax "
|
||||
#define MSG_X "x"
|
||||
#define MSG_Y "y"
|
||||
#define MSG_Z "z"
|
||||
#define MSG_E "e"
|
||||
#define MSG_VMIN "Vmin"
|
||||
#define MSG_VTRAV_MIN "VTrav min"
|
||||
#define MSG_AMAX "Amax "
|
||||
#define MSG_A_RETRACT "A-retract"
|
||||
#define MSG_XSTEPS "Xsteps/mm"
|
||||
#define MSG_YSTEPS "Ysteps/mm"
|
||||
#define MSG_ZSTEPS "Zsteps/mm"
|
||||
#define MSG_ESTEPS "Esteps/mm"
|
||||
#define MSG_TEMPERATURE "Temperature"
|
||||
#define MSG_MOTION "Motion"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
|
||||
#define MSG_CONTRAST "LCD contrast"
|
||||
#define MSG_STORE_EPROM "Store memory"
|
||||
#define MSG_LOAD_EPROM "Load memory"
|
||||
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
#define MSG_REFRESH "\xF8" "Refresh"
|
||||
#define MSG_WATCH "Info screen"
|
||||
#define MSG_PREPARE "Prepare"
|
||||
#define MSG_TUNE "Tune"
|
||||
#define MSG_PAUSE_PRINT "Pause print"
|
||||
#define MSG_RESUME_PRINT "Resume print"
|
||||
|
@ -107,76 +54,66 @@
|
|||
#define MSG_DWELL "Sleep..."
|
||||
#define MSG_USERWAIT "Wait for user..."
|
||||
#define MSG_RESUMING "Resuming print"
|
||||
#define MSG_PRINT_ABORTED "Print aborted"
|
||||
#define(length=20) MSG_PRINT_ABORTED "Print aborted"
|
||||
#define MSG_NO_MOVE "No move."
|
||||
#define MSG_KILLED "KILLED. "
|
||||
#define MSG_STOPPED "STOPPED. "
|
||||
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
|
||||
#define MSG_CONTROL_RETRACTF "Retract V"
|
||||
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
|
||||
#define MSG_AUTORETRACT "AutoRetr."
|
||||
#define MSG_FILAMENTCHANGE "Change filament"
|
||||
#define MSG_INIT_SDCARD "Init. SD card"
|
||||
#define MSG_CNG_SDCARD "Change SD card"
|
||||
#define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
#define MSG_BABYSTEP_Z "Live adjust Z"
|
||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||
#define MSG_ADJUSTZ "Auto adjust Z ?"
|
||||
#define MSG_ADJUSTZ "Auto adjust Z?"
|
||||
#define MSG_PICK_Z "Pick print"
|
||||
|
||||
#define MSG_SETTINGS "Settings"
|
||||
#define MSG_PREHEAT "Preheat"
|
||||
#define MSG_UNLOAD_FILAMENT "Unload filament"
|
||||
#define MSG_LOAD_FILAMENT "Load filament"
|
||||
#define(length=17) MSG_UNLOAD_FILAMENT "Unload filament"
|
||||
#define(length=17) MSG_LOAD_FILAMENT "Load filament"
|
||||
#define(length=17) MSG_LOAD_FILAMENT_1 "Load filament 1"
|
||||
#define(length=17) MSG_LOAD_FILAMENT_2 "Load filament 2"
|
||||
#define(length=17) MSG_LOAD_FILAMENT_3 "Load filament 3"
|
||||
#define(length=17) MSG_LOAD_FILAMENT_4 "Load filament 4"
|
||||
#define(length=17) MSG_UNLOAD_FILAMENT_1 "Unload filament 1"
|
||||
#define(length=17) MSG_UNLOAD_FILAMENT_2 "Unload filament 2"
|
||||
#define(length=17) MSG_UNLOAD_FILAMENT_3 "Unload filament 3"
|
||||
#define(length=17) MSG_UNLOAD_FILAMENT_4 "Unload filament 4"
|
||||
#define MSG_UNLOAD_ALL "Unload all"
|
||||
#define MSG_LOAD_ALL "Load all"
|
||||
|
||||
|
||||
#define MSG_RECTRACT "Rectract"
|
||||
#define MSG_ERROR "ERROR:"
|
||||
#define MSG_PREHEAT_NOZZLE "Preheat the nozzle!"
|
||||
#define(length=20) MSG_PREHEAT_NOZZLE "Preheat the nozzle!"
|
||||
#define MSG_SUPPORT "Support"
|
||||
#define MSG_CORRECTLY "Changed correctly?"
|
||||
#define(length=20) MSG_CORRECTLY "Changed correctly?"
|
||||
#define MSG_YES "Yes"
|
||||
#define MSG_NO "No"
|
||||
#define MSG_NOT_LOADED "Filament not loaded"
|
||||
#define(length=19) MSG_NOT_LOADED "Filament not loaded"
|
||||
#define MSG_NOT_COLOR "Color not clear"
|
||||
#define MSG_LOADING_FILAMENT "Loading filament"
|
||||
#define MSG_PLEASE_WAIT "Please wait"
|
||||
#define(length=20) MSG_LOADING_FILAMENT "Loading filament"
|
||||
#define(length=20) MSG_PLEASE_WAIT "Please wait"
|
||||
#define MSG_LOADING_COLOR "Loading color"
|
||||
#define MSG_CHANGE_SUCCESS "Change success!"
|
||||
#define MSG_PRESS "And press the knob"
|
||||
#define MSG_INSERT_FILAMENT "Insert filament"
|
||||
#define MSG_CHANGING_FILAMENT "Changing filament!"
|
||||
#define(length=20) MSG_PRESS "and press the knob"
|
||||
#define(length=20) MSG_INSERT_FILAMENT "Insert filament"
|
||||
#define(length=20) MSG_CHANGING_FILAMENT "Changing filament!"
|
||||
|
||||
|
||||
#define MSG_SILENT_MODE_ON "Mode [silent]"
|
||||
#define MSG_SILENT_MODE_OFF "Mode [high power]"
|
||||
#define MSG_REBOOT "Reboot the printer"
|
||||
#define MSG_TAKE_EFFECT " for take effect"
|
||||
#define MSG_SILENT_MODE_ON "Mode [Stealth]"
|
||||
#define MSG_SILENT_MODE_OFF "Mode [Normal]"
|
||||
#define(length=20) MSG_REBOOT "Reboot the printer"
|
||||
#define(length=20) MSG_TAKE_EFFECT " for take effect"
|
||||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_EXTERNAL_RESET " External Reset"
|
||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
||||
#define MSG_AUTHOR " | Author: "
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
#define MSG_FILE_PRINTED "Done printing file"
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
|
@ -187,27 +124,16 @@
|
|||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
#define MSG_HEATING "Heating"
|
||||
#define MSG_HEATING_COMPLETE "Heating done."
|
||||
#define(length=20) MSG_HEATING_COMPLETE "Heating done."
|
||||
#define MSG_BED_HEATING "Bed Heating"
|
||||
#define MSG_BED_DONE "Bed done"
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_COUNT_X " Count X: "
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
#define MSG_X_MIN "x_min: "
|
||||
#define MSG_X_MAX "x_max: "
|
||||
#define MSG_Y_MIN "y_min: "
|
||||
#define MSG_Y_MAX "y_max: "
|
||||
#define MSG_Z_MIN "z_min: "
|
||||
#define MSG_Z_MAX "z_max: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
|
@ -217,7 +143,6 @@
|
|||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_SIZE " Size: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
|
@ -228,14 +153,13 @@
|
|||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Adjusting Z"
|
||||
#define(length=20) MSG_BABYSTEPPING_Z "Adjusting Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
|
||||
#define MSG_LANGUAGE_NAME "English"
|
||||
#define MSG_LANGUAGE_SELECT "Select language "
|
||||
#define MSG_LANGUAGE_SELECT "Select language"
|
||||
#define MSG_PRUSA3D "prusa3d.com"
|
||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
|
@ -249,61 +173,198 @@
|
|||
#define MSG_SELFTEST_ENDSTOPS "Endstops"
|
||||
#define MSG_SELFTEST_MOTOR "Motor"
|
||||
#define MSG_SELFTEST_ENDSTOP "Endstop"
|
||||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||
|
||||
#define(length=20,lines=1) MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||
#define MSG_SELFTEST_OK "Self test OK"
|
||||
#define MSG_STATS_TOTALFILAMENT "Total filament :"
|
||||
#define MSG_STATS_TOTALPRINTTIME "Total print time :"
|
||||
#define MSG_STATS_FILAMENTUSED "Filament used: "
|
||||
#define MSG_STATS_PRINTTIME "Print time: "
|
||||
#define MSG_SELFTEST_START "Self test start "
|
||||
#define MSG_SELFTEST_CHECK_ENDSTOPS "Checking endstops"
|
||||
#define MSG_SELFTEST_CHECK_HOTEND "Checking hotend "
|
||||
#define MSG_SELFTEST_CHECK_X "Checking X axis "
|
||||
#define MSG_SELFTEST_CHECK_Y "Checking Y axis "
|
||||
#define MSG_SELFTEST_CHECK_Z "Checking Z axis "
|
||||
#define MSG_SELFTEST_CHECK_BED "Checking bed "
|
||||
#define MSG_SELFTEST_CHECK_ALLCORRECT "All correct "
|
||||
#define(length=20,lines=1) MSG_LOOSE_PULLEY "Loose pulley"
|
||||
|
||||
#define(length=20) MSG_SELFTEST_FAN "Fan test"
|
||||
#define(length=20) MSG_SELFTEST_COOLING_FAN "Front print fan?"
|
||||
#define(length=20) MSG_SELFTEST_EXTRUDER_FAN "Left hotend fan?"
|
||||
#define(length=19) MSG_SELFTEST_FAN_YES "Spinning"
|
||||
#define(length=19) MSG_SELFTEST_FAN_NO "Not spinning"
|
||||
|
||||
#define(length=20) MSG_STATS_TOTALFILAMENT "Total filament :"
|
||||
#define(length=20) MSG_STATS_TOTALPRINTTIME "Total print time :"
|
||||
#define(length=20) MSG_STATS_FILAMENTUSED "Filament used: "
|
||||
#define(length=20) MSG_STATS_PRINTTIME "Print time: "
|
||||
#define(length=20) MSG_SELFTEST_START "Self test start "
|
||||
#define(length=20) MSG_SELFTEST_CHECK_ENDSTOPS "Checking endstops"
|
||||
#define(length=20) MSG_SELFTEST_CHECK_HOTEND "Checking hotend "
|
||||
#define(length=20) MSG_SELFTEST_CHECK_X "Checking X axis "
|
||||
#define(length=20) MSG_SELFTEST_CHECK_Y "Checking Y axis "
|
||||
#define(length=20) MSG_SELFTEST_CHECK_Z "Checking Z axis "
|
||||
#define(length=20) MSG_SELFTEST_CHECK_BED "Checking bed "
|
||||
#define(length=20) MSG_SELFTEST_CHECK_ALLCORRECT "All correct "
|
||||
#define MSG_SELFTEST "Selftest "
|
||||
#define MSG_SELFTEST_FAILED "Selftest failed "
|
||||
#define(length=20) MSG_SELFTEST_FAILED "Selftest failed "
|
||||
#define MSG_STATISTICS "Statistics "
|
||||
#define MSG_USB_PRINTING "USB printing "
|
||||
#define MSG_HOMEYZ "Calibrate Z"
|
||||
#define MSG_HOMEYZ_PROGRESS "Calibrating Z"
|
||||
#define MSG_HOMEYZ_DONE "Calibration done"
|
||||
|
||||
#define MSG_SHOW_END_STOPS "Show end stops"
|
||||
#define MSG_CALIBRATE_BED "Calibrate X/Y"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset X/Y calibr."
|
||||
#define(length=17,lines=1) MSG_SHOW_END_STOPS "Show end stops"
|
||||
#define MSG_CALIBRATE_BED "Calibrate XYZ"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset XYZ calibr."
|
||||
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP "Calibrating X/Y. Move Z carriage up to the end stoppers. Click when done."
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN "Please clean the nozzle for calibration. Click when done."
|
||||
#define MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Are left and right Z~carriages all up?"
|
||||
#define(length=20,lines=8) MSG_MOVE_CARRIAGE_TO_THE_TOP "Calibrating XYZ. Rotate the knob to move the Z carriage up to the end stoppers. Click when done."
|
||||
#define(length=20,lines=8) MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Calibrating Z. Rotate the knob to move the Z carriage up to the end stoppers. Click when done."
|
||||
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Searching bed"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 "calibration point"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE3 " of 4"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Improving bed"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 "calibration point"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE3 " of 9"
|
||||
#define(length=20,lines=8) MSG_CONFIRM_NOZZLE_CLEAN "Please clean the nozzle for calibration. Click when done."
|
||||
#define(length=20,lines=2) MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Are left and right Z~carriages all up?"
|
||||
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "X/Y calibration failed. Bed calibration point was not found."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "X/Y calibration failed. Please consult the manual."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "X/Y calibration ok. X/Y axes are perpendicular."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "X/Y calibration all right. X/Y axes are slightly skewed."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "X/Y skewed severly. Skew will be corrected automatically."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "X/Y calibration failed. Left front calibration point not reachable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "X/Y calibration failed. Right front calibration point not reachable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "X/Y calibration failed. Front calibration points not reachable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "X/Y calibration compromised. Left front calibration point not reachable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "X/Y calibration compromised. Right front calibration point not reachable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "X/Y calibration compromised. Front calibration points not reachable."
|
||||
#define(length=60) MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Searching bed calibration point"
|
||||
#define(length=14) MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " of 4"
|
||||
#define(length=60) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Improving bed calibration point"
|
||||
#define(length=14) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " of 4"
|
||||
#define(length=60) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Measuring reference height of calibration point"
|
||||
#define(length=14) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " of 9"
|
||||
#define(length=20) MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteration "
|
||||
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_LOW "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_HIGH "Bed leveling failed. Sensor triggered too high. Waiting for reset."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "XYZ calibration failed. Bed calibration point was not found."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "XYZ calibration failed. Please consult the manual."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "XYZ calibration ok. X/Y axes are perpendicular. Congratulations!"
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "XYZ calibration all right. Skew will be corrected automatically."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "XYZ calibration failed. Left front calibration point not reachable."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "XYZ calibration failed. Right front calibration point not reachable."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "XYZ calibration failed. Front calibration points not reachable."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "XYZ calibration compromised. Left front calibration point not reachable."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "XYZ calibration compromised. Right front calibration point not reachable."
|
||||
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "XYZ calibration compromised. Front calibration points not reachable."
|
||||
|
||||
#define MSG_NEW_FIRMWARE_AVAILABLE "New firmware version available:"
|
||||
#define MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Please upgrade."
|
||||
#define(length=20,lines=4) MSG_BED_LEVELING_FAILED_POINT_LOW "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
|
||||
#define(length=20,lines=4) MSG_BED_LEVELING_FAILED_POINT_HIGH "Bed leveling failed. Sensor triggered too high. Waiting for reset."
|
||||
#define(length=20,lines=4) MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Bed leveling failed. Sensor disconnected or cable broken. Waiting for reset."
|
||||
|
||||
#define MSG_BABYSTEP_Z_NOT_SET "Printer has not been calibrated yet. Run calibration G-code to adjust Z height."
|
||||
#define(length=20,lines=2) MSG_NEW_FIRMWARE_AVAILABLE "New firmware version available:"
|
||||
#define(length=20) MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Please upgrade."
|
||||
|
||||
#endif // LANGUAGE_EN_H
|
||||
#define(length=20,lines=8) MSG_FOLLOW_CALIBRATION_FLOW "Printer has not been calibrated yet. Please follow the manual, chapter First steps, section Calibration flow."
|
||||
#define(length=20,lines=12) MSG_BABYSTEP_Z_NOT_SET "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
|
||||
|
||||
#define(length=20, lines=4) MSG_FILAMENT_LOADING_T0 "Insert filament into extruder 1. Click when done."
|
||||
#define(length=20, lines=4) MSG_FILAMENT_LOADING_T1 "Insert filament into extruder 2. Click when done."
|
||||
#define(length=20, lines=4) MSG_FILAMENT_LOADING_T2 "Insert filament into extruder 3. Click when done."
|
||||
#define(length=20, lines=4) MSG_FILAMENT_LOADING_T3 "Insert filament into extruder 4. Click when done."
|
||||
#define(length=20, lines=1) MSG_CHANGE_EXTR "Change extruder"
|
||||
|
||||
#define(length=20, lines=4) MSG_FIL_ADJUSTING "Adjusting filaments. Please wait."
|
||||
#define(length=20,lines=8) MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filaments are now adjusted. Please clean the nozzle for calibration. Click when done."
|
||||
#define(length=20, lines=4) MSG_STACK_ERROR "Error - static memory has been overwritten"
|
||||
#define(length=20, lines=1) MSG_CALIBRATE_E "Calibrate E"
|
||||
//#define(length=20, lines=1) MSG_RESET_CALIBRATE_E "Reset E Cal."
|
||||
#define(length=20, lines=8) MSG_E_CAL_KNOB "Rotate knob until mark reaches extruder body. Click when done."
|
||||
|
||||
//#define(length=20, lines=1) MSG_FARM_CARD_MENU "Farm mode print"
|
||||
#define(length=20, lines=8) MSG_MARK_FIL "Mark filament 100mm from extruder body. Click when done."
|
||||
#define(length=20, lines=8) MSG_CLEAN_NOZZLE_E "E calibration finished. Please clean the nozzle. Click when done."
|
||||
#define(length=20, lines=3) MSG_WAITING_TEMP "Waiting for nozzle and bed cooling"
|
||||
#define(length=20, lines=2) MSG_FILAMENT_CLEAN "Is color clear?"
|
||||
#define(lenght=18, lines=1) MSG_UNLOADING_FILAMENT "Unloading filament"
|
||||
#define(length=20, lines=8) MSG_PAPER "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
|
||||
|
||||
#define MSG_BED_CORRECTION_MENU "Bed level correct"
|
||||
#define(length=14,lines=1) MSG_BED_CORRECTION_LEFT "Left side [um]"
|
||||
#define(length=14,lines=1) MSG_BED_CORRECTION_RIGHT "Right side[um]"
|
||||
#define(length=14,lines=1) MSG_BED_CORRECTION_FRONT "Front side[um]"
|
||||
#define(length=14,lines=1) MSG_BED_CORRECTION_REAR "Rear side [um]"
|
||||
#define MSG_BED_CORRECTION_RESET "Reset"
|
||||
|
||||
#define MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
#define MSG_MENU_CALIBRATION "Calibration"
|
||||
#define(length=19, lines=1) MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
#define(length=19, lines=1) MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
#define(length=20, lines=1) MSG_PRINTER_DISCONNECTED "Printer disconnected"
|
||||
#define(length=20, lines=1) MSG_FINISHING_MOVEMENTS "Finishing movements"
|
||||
#define(length=20, lines=1) MSG_PRINT_PAUSED "Print paused"
|
||||
#define(length=20, lines=1) MSG_RESUMING_PRINT "Resuming print"
|
||||
#define(length=17, lines=1) MSG_PID_EXTRUDER "PID calibration"
|
||||
#define(length=19, lines=1) MSG_SET_TEMPERATURE "Set temperature:"
|
||||
#define(length=20, lines=1) MSG_PID_FINISHED "PID cal. finished"
|
||||
#define(length=20, lines=1) MSG_PID_RUNNING "PID cal. "
|
||||
|
||||
#define(length=17, lines=1) MSG_CALIBRATE_PINDA "Calibrate"
|
||||
#define(length=17, lines=1) MSG_CALIBRATION_PINDA_MENU "Temp. calibration"
|
||||
#define(length=20, lines=4) MSG_PINDA_NOT_CALIBRATED "Temperature calibration has not been run yet"
|
||||
#define(length=20, lines=1) MSG_PINDA_PREHEAT "PINDA Heating"
|
||||
#define(length=20, lines=1) MSG_TEMP_CALIBRATION "Temp. cal. "
|
||||
#define(length=20, lines=4) MSG_TEMP_CALIBRATION_DONE "Temperature calibration is finished. Click to continue."
|
||||
#define(length=20, lines=1) MSG_TEMP_CALIBRATION_ON "Temp. cal. [on]"
|
||||
#define(length=20, lines=1) MSG_TEMP_CALIBRATION_OFF "Temp. cal. [off]"
|
||||
#define(length=20, lines=1) MSG_PREPARE_FILAMENT "Prepare new filament"
|
||||
#define(length=19, lines=1) MSG_ALL "All"
|
||||
#define(length=19, lines=1) MSG_USED "Used during print"
|
||||
#define(length=19, lines=1) MSG_CURRENT "Current"
|
||||
#define(length=20, lines=1) MSG_CHOOSE_EXTRUDER "Choose extruder:"
|
||||
#define(length=17, lines=1) MSG_EXTRUDER "Extruder"
|
||||
#define(length=17, lines=1) MSG_EXTRUDER_1 "Extruder 1"
|
||||
#define(length=17, lines=1) MSG_EXTRUDER_2 "Extruder 2"
|
||||
#define(length=17, lines=1) MSG_EXTRUDER_3 "Extruder 3"
|
||||
#define(length=17, lines=1) MSG_EXTRUDER_4 "Extruder 4"
|
||||
|
||||
//Wizard messages which has tranlsations
|
||||
|
||||
#define(length=17, lines=1) MSG_WIZARD "Wizard"
|
||||
#define(length=20, lines=7) MSG_WIZARD_WELCOME "Hi, I am your Original Prusa i3 printer. Would you like me to guide you through the setup process?"
|
||||
#define(length=20, lines=8) MSG_WIZARD_QUIT "You can always resume the Wizard from Calibration -> Wizard."
|
||||
#define(length=20, lines=8) MSG_WIZARD_SELFTEST "First, I will run the selftest to check most common assembly problems."
|
||||
#define(length=20, lines=8) MSG_WIZARD_CALIBRATION_FAILED "Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
#define(length=20, lines=8) MSG_WIZARD_XYZ_CAL "I will run xyz calibration now. It will take approx. 12 mins."
|
||||
#define(length=20, lines=2) MSG_WIZARD_FILAMENT_LOADED "Is filament loaded?"
|
||||
#define(length=20, lines=8) MSG_WIZARD_Z_CAL "I will run z calibration now."
|
||||
#define(length=20, lines=4) MSG_WIZARD_WILL_PREHEAT "Now I will preheat nozzle for PLA."
|
||||
#define(length=20, lines=3) MSG_WIZARD_HEATING "Preheating nozzle. Please wait."
|
||||
#define(lenght=20, lines=8) MSG_WIZARD_V2_CAL "Now I will calibrate distance between tip of the nozzle and heatbed surface."
|
||||
#define(lenght=20, lines=12) MSG_WIZARD_V2_CAL_2 "I will start to print line and you will gradually lower the nozzle by rotating the knob, until you reach optimal height. Check the pictures in our handbook in chapter Calibration."
|
||||
#define(lenght=17, lines=1) MSG_V2_CALIBRATION "First layer cal."
|
||||
#define(lenght=20, lines=8) MSG_WIZARD_DONE "All is done. Happy printing!"
|
||||
#define(lenght=20, lines=8) MSG_WIZARD_LOAD_FILAMENT "Please insert PLA filament to the extruder, then press knob to load it."
|
||||
#define(lenght=20, lines=7) MSG_WIZARD_RERUN "Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
#define(lenght=20, lines=7) MSG_WIZARD_REPEAT_V2_CAL "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
|
||||
#define(lenght=20, lines=8) MSG_WIZARD_CLEAN_HEATBED "Please clean heatbed and then press the knob."
|
||||
#define(lenght=20, lines=2) MSG_WIZARD_PLA_FILAMENT "Is it PLA filament?"
|
||||
#define(lenght=20, lines=8) MSG_WIZARD_INSERT_CORRECT_FILAMENT "Please load PLA filament and then resume Wizard by rebooting the printer."
|
||||
#define(lenght=20, lines=2) MSG_PLA_FILAMENT_LOADED "Is PLA filament loaded?"
|
||||
#define(lenght=20, lines=4) MSG_PLEASE_LOAD_PLA "Please load PLA filament first."
|
||||
#define(length=25, lines=1) MSG_M117_V2_CALIBRATION "M117 First layer cal."
|
||||
|
||||
#define(length=17, lines=1) MSG_DATE "Date:"
|
||||
#define(length=19, lines=1) MSG_XYZ_DETAILS "XYZ cal. details"
|
||||
#define(length=20, lines=1) MSG_Y_DISTANCE_FROM_MIN "Y distance from min:"
|
||||
#define(length=12, lines=1) MSG_LEFT "Left:"
|
||||
#define(length=12, lines=1) MSG_RIGHT "Right:"
|
||||
#define(length=15, lines=1) MSG_MEASURED_SKEW "Measured skew:"
|
||||
#define(length=15, lines=1) MSG_SLIGHT_SKEW "Slight skew:"
|
||||
#define(length=15, lines=1) MSG_SEVERE_SKEW "Severe skew:"
|
||||
|
||||
//messages bellow has no translation yet
|
||||
|
||||
#define MSG_CRASHDETECT_OFF "Crash det. [off]"
|
||||
#define MSG_CRASHDETECT_ON "Crash det. [on]"
|
||||
#define MSG_FSENSOR_OFF "Fil. sensor [off]"
|
||||
#define MSG_FSENSOR_ON "Fil. sensor [on]"
|
||||
|
||||
#define(length=20, lines=4) MSG_PLACE_STEEL_SHEET "Please place steel sheet on heatbed."
|
||||
#define(length=20, lines=4) MSG_REMOVE_STEEL_SHEET "Please remove steel sheet from heatbed."
|
||||
#define(length=20, lines=2) MSG_CALIBRATE_Z_AUTO "Calibrating Z"
|
||||
#define(length=20, lines=2) MSG_STEEL_SHEET_CHECK "Is steel sheet on heatbed?"
|
||||
|
||||
#define MSG_SELFTEST_AXIS "Axis"
|
||||
#define MSG_SELFTEST_AXIS_LENGTH "Axis length"
|
||||
|
||||
#define(length=20, lines=2) MSG_RECOVER_PRINT "Blackout occurred. Recover print?"
|
||||
#define(length=20, lines=1) MSG_RECOVERING_PRINT "Recovering print "
|
||||
#define(length=20, lines=2) MSG_CRASH_DETECTED "Crash detected. Continue printing?"
|
||||
|
||||
#define(length=15, lines=1) MSG_INFO_EXTRUDER "Extruder info"
|
||||
|
||||
#define(length=11, lines=1) MSG_INFO_NOZZLE_FAN "Nozzle FAN:"
|
||||
#define(length=11, lines=1) MSG_INFO_PRINT_FAN "Print FAN: "
|
||||
#define(length=11, lines=1) MSG_INFO_FILAMENT_XDIFF "Fil. Xd:"
|
||||
#define(length=11, lines=1) MSG_INFO_FILAMENT_YDIFF "Fil. Ydiff:"
|
||||
#define(length=17, lines=1) MSG_FANS_CHECK_ON "Fans check [on]"
|
||||
#define(length=17, lines=1) MSG_FANS_CHECK_OFF "Fans check [off]"
|
||||
#define(length=20, lines=4) MSG_PRESS_TO_UNLOAD "Please press the knob to unload filament"
|
||||
#define(length=20, lines=2) MSG_UNLOAD_SUCCESSFULL "Repeat unloading filament?"
|
||||
|
|
|
@ -5,11 +5,9 @@
|
|||
* Please note these are limited to 17 characters!
|
||||
*
|
||||
*/
|
||||
#ifndef LANGUAGE_ES_H
|
||||
#define LANGUAGE_ES_H
|
||||
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " lista"
|
||||
#define MSG_SD_INSERTED "Tarjeta colocada"
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " prep."
|
||||
#define MSG_SD_INSERTED "Tarjeta insertada"
|
||||
#define MSG_SD_REMOVED "Tarjeta retirada"
|
||||
#define MSG_MAIN "Menu principal"
|
||||
#define MSG_DISABLE_STEPPERS "Apagar motores"
|
||||
|
@ -19,11 +17,11 @@
|
|||
#define MSG_MOVE_X "Mover X"
|
||||
#define MSG_MOVE_Y "Mover Y"
|
||||
#define MSG_MOVE_Z "Mover Z"
|
||||
#define MSG_MOVE_E "Extrusor"
|
||||
#define MSG_MOVE_E "Extruir"
|
||||
#define MSG_SPEED "Velocidad"
|
||||
#define MSG_NOZZLE "Fusor"
|
||||
#define MSG_BED "Base"
|
||||
#define MSG_FAN_SPEED "Ventilador"
|
||||
#define MSG_NOZZLE "Nozzle"
|
||||
#define MSG_BED "Heatbed"
|
||||
#define MSG_FAN_SPEED "Velocidad Vent."
|
||||
#define MSG_FLOW "Flujo"
|
||||
#define MSG_TEMPERATURE "Temperatura"
|
||||
#define MSG_WATCH "Monitorizar"
|
||||
|
@ -31,49 +29,49 @@
|
|||
#define MSG_PAUSE_PRINT "Pausar impresion"
|
||||
#define MSG_RESUME_PRINT "Reanudar impres."
|
||||
#define MSG_STOP_PRINT "Detener impresion"
|
||||
#define MSG_CARD_MENU "Menu de SD"
|
||||
#define MSG_CARD_MENU "Menu tarjeta SD"
|
||||
#define MSG_NO_CARD "No hay tarjeta SD"
|
||||
#define MSG_DWELL "Reposo..."
|
||||
#define MSG_DWELL "En espera"
|
||||
#define MSG_USERWAIT "Esperando ordenes"
|
||||
#define MSG_RESUMING "Resumiendo impre."
|
||||
#define MSG_PRINT_ABORTED "Print aborted"
|
||||
#define MSG_RESUMING "Resumiendo impresion"
|
||||
#define MSG_PRINT_ABORTED "Impresion cancelada"
|
||||
#define MSG_NO_MOVE "Sin movimiento"
|
||||
#define MSG_KILLED "PARADA DE EMERG."
|
||||
#define MSG_KILLED "PARADA DE EMERGENCIA"
|
||||
#define MSG_STOPPED "PARADA"
|
||||
#define MSG_FILAMENTCHANGE "Cambiar filamento"
|
||||
#define MSG_BABYSTEP_Z "Micropaso Z"
|
||||
#define MSG_ADJUSTZ "Auto Micropaso Z?"
|
||||
#define MSG_PICK_Z "Vyberte vytisk"
|
||||
#define MSG_BABYSTEP_Z "Micropaso Eje Z"
|
||||
#define MSG_ADJUSTZ "Ajustar Eje Z"
|
||||
#define MSG_PICK_Z "Esc. Modelo Adecuado"
|
||||
|
||||
#define MSG_SETTINGS "Ajuste"
|
||||
#define MSG_SETTINGS "Configuracion"
|
||||
#define MSG_PREHEAT "Precalentar"
|
||||
#define MSG_UNLOAD_FILAMENT "Sacar filamento"
|
||||
#define MSG_LOAD_FILAMENT "Introducir filamento"
|
||||
#define MSG_UNLOAD_FILAMENT "Soltar filamento"
|
||||
#define MSG_LOAD_FILAMENT "Introducir filam."
|
||||
#define MSG_ERROR "ERROR:"
|
||||
#define MSG_PREHEAT_NOZZLE "Precal. extrusor!"
|
||||
#define MSG_SUPPORT "Support"
|
||||
#define MSG_CORRECTLY "Cambiado correc.?"
|
||||
#define MSG_PREHEAT_NOZZLE "Precalentar extrusor"
|
||||
#define MSG_SUPPORT "Soporte"
|
||||
#define MSG_CORRECTLY "Cambiado correct.?"
|
||||
#define MSG_YES "Si"
|
||||
#define MSG_NO "No"
|
||||
#define MSG_NOT_LOADED "Fil. no cargado"
|
||||
#define MSG_NOT_COLOR "Color no claro"
|
||||
#define MSG_LOADING_FILAMENT "Cargando fil."
|
||||
#define MSG_PLEASE_WAIT "Espera"
|
||||
#define MSG_LOADING_COLOR "Cargando color"
|
||||
#define MSG_CHANGE_SUCCESS "Cambiar bien!"
|
||||
#define MSG_PRESS "Y pulse el mando"
|
||||
#define MSG_INSERT_FILAMENT "Inserta filamento"
|
||||
#define MSG_CHANGING_FILAMENT "Cambiando fil.!"
|
||||
#define MSG_SILENT_MODE_ON "Modo [silencio]"
|
||||
#define MSG_SILENT_MODE_OFF "Modo [mas fuerza]"
|
||||
#define MSG_REBOOT "Reiniciar la imp."
|
||||
#define MSG_TAKE_EFFECT "para tomar efecto"
|
||||
#define MSG_NOT_LOADED "Fil. no introducido"
|
||||
#define MSG_NOT_COLOR "Color no homogeneo"
|
||||
#define MSG_LOADING_FILAMENT "Introduciendo filam."
|
||||
#define MSG_PLEASE_WAIT "Por Favor Esperar"
|
||||
#define MSG_LOADING_COLOR "Cambiando color"
|
||||
#define MSG_CHANGE_SUCCESS "Cambio correcto"
|
||||
#define MSG_PRESS "Haz clic"
|
||||
#define MSG_INSERT_FILAMENT "Introducir filamento"
|
||||
#define MSG_CHANGING_FILAMENT "Cambiando filamento"
|
||||
#define MSG_SILENT_MODE_ON "Modo [silencio]"
|
||||
#define MSG_SILENT_MODE_OFF "Modo [rend.pleno]"
|
||||
#define MSG_REBOOT "Reiniciar impresora"
|
||||
#define MSG_TAKE_EFFECT " para aplicar cambios"
|
||||
#define MSG_HEATING "Calentando..."
|
||||
#define MSG_HEATING_COMPLETE "Calentando listo."
|
||||
#define MSG_BED_HEATING "Base Calentando"
|
||||
#define MSG_BED_DONE "Base listo."
|
||||
#define MSG_HEATING_COMPLETE "Calentamiento final."
|
||||
#define MSG_BED_HEATING "Calentando Base"
|
||||
#define MSG_BED_DONE "Base preparada"
|
||||
#define MSG_LANGUAGE_NAME "Espanol"
|
||||
#define MSG_LANGUAGE_SELECT "Cambia la lengua "
|
||||
#define MSG_LANGUAGE_SELECT "Cambiae el idioma"
|
||||
#define MSG_PRUSA3D "prusa3d.com"
|
||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
|
@ -83,21 +81,12 @@
|
|||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_EXTERNAL_RESET " External Reset"
|
||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
||||
#define MSG_AUTHOR " | Author: "
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
#define MSG_FILE_PRINTED "Done printing file"
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
|
@ -108,23 +97,12 @@
|
|||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_COUNT_X " Count X: "
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
#define MSG_X_MIN "x_min: "
|
||||
#define MSG_X_MAX "x_max: "
|
||||
#define MSG_Y_MIN "y_min: "
|
||||
#define MSG_Y_MAX "y_max: "
|
||||
#define MSG_Z_MIN "z_min: "
|
||||
#define MSG_Z_MAX "z_max: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
#define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
|
@ -133,7 +111,6 @@
|
|||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_SIZE " Size: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
|
@ -143,61 +120,14 @@
|
|||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Adjusting Z"
|
||||
#define MSG_BABYSTEPPING_Z "Ajustar Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
#define MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
#define MSG_SET_ORIGIN "Set origin"
|
||||
#define MSG_PREHEAT_PLA "Preheat PLA"
|
||||
#define MSG_PREHEAT_PLA0 "Preheat PLA 1"
|
||||
#define MSG_PREHEAT_PLA1 "Preheat PLA 2"
|
||||
#define MSG_PREHEAT_PLA2 "Preheat PLA 3"
|
||||
#define MSG_PREHEAT_PLA012 "Preheat PLA All"
|
||||
#define MSG_PREHEAT_PLA_BEDONLY "Preheat PLA Bed"
|
||||
#define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA conf"
|
||||
#define MSG_PREHEAT_ABS "Preheat ABS"
|
||||
#define MSG_PREHEAT_ABS0 "Preheat ABS 1"
|
||||
#define MSG_PREHEAT_ABS1 "Preheat ABS 2"
|
||||
#define MSG_PREHEAT_ABS2 "Preheat ABS 3"
|
||||
#define MSG_PREHEAT_ABS012 "Preheat ABS All"
|
||||
#define MSG_PREHEAT_ABS_BEDONLY "Preheat ABS Bed"
|
||||
#define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS conf"
|
||||
#define MSG_SWITCH_PS_ON "Switch power on"
|
||||
#define MSG_SWITCH_PS_OFF "Switch power off"
|
||||
#define MSG_AUTOTEMP "Autotemp"
|
||||
#define MSG_ON "On "
|
||||
#define MSG_OFF "Off"
|
||||
#define MSG_PID_P "PID-P"
|
||||
#define MSG_PID_I "PID-I"
|
||||
#define MSG_PID_D "PID-D"
|
||||
#define MSG_PID_C "PID-C"
|
||||
#define MSG_ACC "Accel"
|
||||
#define MSG_VXY_JERK "Vxy-jerk"
|
||||
#define MSG_VZ_JERK "Vz-jerk"
|
||||
#define MSG_VE_JERK "Ve-jerk"
|
||||
#define MSG_VMAX "Vmax "
|
||||
#define MSG_X "x"
|
||||
#define MSG_Y "y"
|
||||
#define MSG_Z "z"
|
||||
#define MSG_E "e"
|
||||
#define MSG_VMIN "Vmin"
|
||||
#define MSG_VTRAV_MIN "VTrav min"
|
||||
#define MSG_AMAX "Amax "
|
||||
#define MSG_A_RETRACT "A-retract"
|
||||
#define MSG_XSTEPS "Xsteps/mm"
|
||||
#define MSG_YSTEPS "Ysteps/mm"
|
||||
#define MSG_ZSTEPS "Zsteps/mm"
|
||||
#define MSG_ESTEPS "Esteps/mm"
|
||||
#define MSG_RETRACT "Retract"
|
||||
#define MSG_EXTRUDE "Extrude"
|
||||
#define MSG_AUTOSTART "Autostart"
|
||||
#define MSG_MOVE_E1 "Extruder2"
|
||||
#define MSG_MOVE_E2 "Extruder3"
|
||||
#define MSG_MOVE_01MM "Move 0.1mm"
|
||||
#define MSG_MOVE_1MM "Move 1mm"
|
||||
#define MSG_MOVE_10MM "Move 10mm"
|
||||
#define MSG_NOZZLE1 "Nozzle2"
|
||||
#define MSG_NOZZLE2 "Nozzle3"
|
||||
#define MSG_FLOW0 "Flow 0"
|
||||
|
@ -210,31 +140,14 @@
|
|||
#define MSG_MOTION "Motion"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
|
||||
#define MSG_CONTRAST "LCD contrast"
|
||||
#define MSG_STORE_EPROM "Store memory"
|
||||
#define MSG_LOAD_EPROM "Load memory"
|
||||
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
#define MSG_REFRESH "\xF8" "Refresh"
|
||||
#define MSG_PREPARE "Prepare"
|
||||
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
|
||||
#define MSG_CONTROL_RETRACTF "Retract V"
|
||||
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
|
||||
#define MSG_AUTORETRACT "AutoRetr."
|
||||
#define MSG_INIT_SDCARD "Init. SD card"
|
||||
#define MSG_CNG_SDCARD "Change SD card"
|
||||
#define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||
#define MSG_RECTRACT "Rectract"
|
||||
|
||||
#define MSG_HOMEYZ "Calibrar Z"
|
||||
|
@ -244,33 +157,166 @@
|
|||
#define MSG_SELFTEST_ERROR "Autotest error!"
|
||||
#define MSG_SELFTEST_PLEASECHECK "Controla :"
|
||||
#define MSG_SELFTEST_NOTCONNECTED "No hay conexion "
|
||||
#define MSG_SELFTEST_HEATERTHERMISTOR "Calent./Termistor"
|
||||
#define MSG_SELFTEST_BEDHEATER "Cama/Calentador"
|
||||
#define MSG_SELFTEST_WIRINGERROR "Error de conexión"
|
||||
#define MSG_SELFTEST_ENDSTOPS "Topes final"
|
||||
#define MSG_SELFTEST_HEATERTHERMISTOR "Hotend"
|
||||
#define MSG_SELFTEST_BEDHEATER "Heatbed"
|
||||
#define MSG_SELFTEST_WIRINGERROR "Error de conexion"
|
||||
#define MSG_SELFTEST_ENDSTOPS "Topes finales"
|
||||
#define MSG_SELFTEST_MOTOR "Motor"
|
||||
#define MSG_SELFTEST_ENDSTOP "Tope final"
|
||||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Tope fin. no toc."
|
||||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Tope no alcanzado"
|
||||
#define MSG_SELFTEST_OK "Self test OK"
|
||||
|
||||
#define MSG_SELFTEST_FAN "Test ventiladores"
|
||||
#define MSG_SELFTEST_COOLING_FAN "Vent. frontal?"
|
||||
#define MSG_SELFTEST_EXTRUDER_FAN "Vent. izquierdo?"
|
||||
#define MSG_SELFTEST_FAN_YES "Ventilador gira"
|
||||
#define MSG_SELFTEST_FAN_NO "Ventilador no gira"
|
||||
|
||||
#define MSG_STATS_TOTALFILAMENT "Filamento total:"
|
||||
#define MSG_STATS_TOTALPRINTTIME "Tiempo total :"
|
||||
#define MSG_STATS_FILAMENTUSED "Filamento : "
|
||||
#define MSG_STATS_FILAMENTUSED "Filamento usado: "
|
||||
#define MSG_STATS_PRINTTIME "Tiempo de imp.:"
|
||||
|
||||
#define MSG_SELFTEST_START "Autotest salida"
|
||||
#define MSG_SELFTEST_CHECK_ENDSTOPS "Cont. topes final"
|
||||
#define MSG_SELFTEST_START "Inicio Selftest"
|
||||
#define MSG_SELFTEST_CHECK_ENDSTOPS "Control topes"
|
||||
#define MSG_SELFTEST_CHECK_HOTEND "Control hotend "
|
||||
#define MSG_SELFTEST_CHECK_X "Control del eje X"
|
||||
#define MSG_SELFTEST_CHECK_Y "Control del eje Y"
|
||||
#define MSG_SELFTEST_CHECK_Z "Control del eje Z"
|
||||
#define MSG_SELFTEST_CHECK_BED "Control de cama"
|
||||
#define MSG_SELFTEST_CHECK_ALLCORRECT "Todo bie "
|
||||
#define MSG_SELFTEST "Autotest"
|
||||
#define MSG_SELFTEST_FAILED "Autotest fallado"
|
||||
#define MSG_SELFTEST_CHECK_X "Control tope X"
|
||||
#define MSG_SELFTEST_CHECK_Y "Control tope Y"
|
||||
#define MSG_SELFTEST_CHECK_Z "Control tope Z"
|
||||
#define MSG_SELFTEST_CHECK_BED "Control heatbed"
|
||||
#define MSG_SELFTEST_CHECK_ALLCORRECT "Todo bien"
|
||||
#define MSG_SELFTEST "Selftest"
|
||||
#define MSG_SELFTEST_FAILED "Fallo Selftest"
|
||||
|
||||
#define MSG_STATISTICS "Estadistica "
|
||||
#define MSG_USB_PRINTING "Impresion de USB "
|
||||
#define MSG_STATISTICS "Estadisticas "
|
||||
#define MSG_USB_PRINTING "Impresion con USB "
|
||||
|
||||
#endif // LANGUAGE_EN_H
|
||||
#define MSG_SHOW_END_STOPS "Ensena tope final"
|
||||
#define MSG_CALIBRATE_BED "Calibra XYZ"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset XYZ calibr."
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP "Calibrando XYZ. Gira el boton para subir el extrusor hasta tocar los topes superiores. Despues haz clic."
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Calibrando Z. Gira el boton para subir el extrusor hasta tocar los topes superiores. Despues haz clic."
|
||||
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN "Limpia nozzle para calibracion. Click cuando acabes."
|
||||
#define MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Carros Z izq./der. estan arriba maximo?"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Buscando punto de calibracion heatbed"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " de 4"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Mejorando punto de calibracion heatbed"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " de 4"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Midiendo altura del punto de calibracion"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " de 9"
|
||||
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Reiteracion "
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Calibracion XYZ fallada. Puntos de calibracion en heatbed no encontrados."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Calibracion XYZ fallada. Consulta el manual por favor."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Calibracion XYZ ok. Ejes X/Y perpendiculares. Enhorabuena!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Calibracion XYZ correcta. Los ejes X / Y estan ligeramente inclinados. Buen trabajo!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Calibracion XYZ correcta. La inclinacion se corregira automaticamente."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Calibracion XYZ fallada. Punto frontal izquierdo no alcanzable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Calibracion XYZ fallad. Punto frontal derecho no alcanzable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Calibracion XYZ fallada. Puntos frontales no alcanzables."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Calibrazion XYZ comprometida. Punto frontal izquierdo no alcanzable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Calibrazion XYZ comprometida. Punto frontal derecho no alcanzable."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Calibrazion XYZ comprometida. Puntos frontales no alcanzables."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_LOW "Nivelacion fallada. Sensor no funciona. Escombros en nozzle? Esperando reset."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_HIGH "Nivelacion fallada. Sensor funciona demasiado temprano. Esperando reset."
|
||||
#define MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Nivelacion fallada. Sensor desconectado o cables danados. Esperando reset."
|
||||
#define MSG_NEW_FIRMWARE_AVAILABLE "Nuevo firmware disponible:"
|
||||
#define MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Actualizar por favor"
|
||||
#define MSG_FOLLOW_CALIBRATION_FLOW "Impresora no esta calibrada todavia. Por favor usa el manual, capitulo First steps, Calibration flow."
|
||||
#define MSG_BABYSTEP_Z_NOT_SET "Distancia entre la punta del nozzle y la superficie de la heatbed aun no fijada. Por favor siga el manual, capitulo First steps, First layer calibration."
|
||||
#define MSG_BED_CORRECTION_MENU "Corr. de la cama"
|
||||
#define MSG_BED_CORRECTION_LEFT "Izquierda [um]"
|
||||
#define MSG_BED_CORRECTION_RIGHT "Derecha [um]"
|
||||
#define MSG_BED_CORRECTION_FRONT "Frontal [um]"
|
||||
#define MSG_BED_CORRECTION_REAR "Trasera [um]"
|
||||
#define MSG_BED_CORRECTION_RESET "Reset"
|
||||
|
||||
#define MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
#define MSG_MENU_CALIBRATION "Calibracion"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
|
||||
#define MSG_LOOSE_PULLEY "Polea suelta"
|
||||
#define MSG_FILAMENT_LOADING_T0 "Insertar filamento en el extrusor 1. Haz clic una vez terminado."
|
||||
#define MSG_FILAMENT_LOADING_T1 "Insertar filamento en el extrusor 2. Haz clic una vez terminado."
|
||||
#define MSG_FILAMENT_LOADING_T2 "Insertar filamento en el extrusor 3. Haz clic una vez terminado."
|
||||
#define MSG_FILAMENT_LOADING_T3 "Insertar filamento en el extrusor 4. Haz clic una vez terminado."
|
||||
#define MSG_CHANGE_EXTR "Cambiar extrusor."
|
||||
|
||||
#define MSG_FIL_ADJUSTING "Ajustando filamentos. Espera por favor."
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamentos ajustados. Limpia nozzle para calibracion. Haz clic una vez terminado."
|
||||
#define MSG_CALIBRATE_E "Calibrar E"
|
||||
#define MSG_E_CAL_KNOB "Rotar el mando hasta que la marca llegue al cuerpo del extrusor. Haz clic una vez terminado."
|
||||
#define MSG_MARK_FIL "Marque el filamento 100 mm por encima del final del extrusor. Haz clic una vez terminado."
|
||||
#define MSG_CLEAN_NOZZLE_E "E calibrado. Limpia nozzle. Haz clic una vez terminado."
|
||||
#define MSG_WAITING_TEMP "Esperando enfriamiento de heatbed y extrusor."
|
||||
#define MSG_FILAMENT_CLEAN "Es el nuevo color nitido?"
|
||||
#define MSG_UNLOADING_FILAMENT "Soltando filamento"
|
||||
#define MSG_PAPER "Colocar una hoja de papel sobre la superficie de impresion durante la calibracion de los primeros 4 puntos. Si la boquilla mueve el papel, apagar impresora inmediatamente."
|
||||
|
||||
#define MSG_FINISHING_MOVEMENTS "Term. movimientos"
|
||||
#define MSG_PRINT_PAUSED "Impresion en pausa"
|
||||
#define MSG_RESUMING_PRINT "Reanudar impresion"
|
||||
#define MSG_PID_EXTRUDER "Calibracion PID"
|
||||
#define MSG_SET_TEMPERATURE "Establecer temp.:"
|
||||
#define MSG_PID_FINISHED "Cal. PID terminada"
|
||||
#define MSG_PID_RUNNING "Cal. PID "
|
||||
|
||||
#define MSG_CALIBRATE_PINDA "Calibrar"
|
||||
#define MSG_CALIBRATION_PINDA_MENU "Calibracion temp."
|
||||
#define MSG_PINDA_NOT_CALIBRATED "La temperatura de calibracion no ha sido ajustada"
|
||||
#define MSG_PINDA_PREHEAT "Calentando PINDA"
|
||||
#define MSG_TEMP_CALIBRATION "Cal. temp. "
|
||||
#define MSG_TEMP_CALIBRATION_DONE "Calibracon temperatura terminada. Haz clic para continuar."
|
||||
#define MSG_TEMP_CALIBRATION_ON "Cal. temp. [ON]"
|
||||
#define MSG_TEMP_CALIBRATION_OFF "Cal. temp. [OFF]"
|
||||
|
||||
#define MSG_PREPARE_FILAMENT "Preparar filamento"
|
||||
|
||||
|
||||
|
||||
#define MSG_LOAD_ALL "Intr. todos fil."
|
||||
#define MSG_LOAD_FILAMENT_1 "Introducir fil. 1"
|
||||
#define MSG_LOAD_FILAMENT_2 "Introducir fil. 2"
|
||||
#define MSG_LOAD_FILAMENT_3 "Introducir fil. 3"
|
||||
#define MSG_LOAD_FILAMENT_4 "Introducir fil. 4"
|
||||
#define MSG_UNLOAD_FILAMENT_1 "Soltar fil. 1"
|
||||
#define MSG_UNLOAD_FILAMENT_2 "Soltar fil. 2"
|
||||
#define MSG_UNLOAD_FILAMENT_3 "Soltar fil. 3"
|
||||
#define MSG_UNLOAD_FILAMENT_4 "Soltar fil. 4"
|
||||
#define MSG_UNLOAD_ALL "Soltar todos fil."
|
||||
#define MSG_PREPARE_FILAMENT "Preparar filamento"
|
||||
#define MSG_ALL "Todos"
|
||||
#define MSG_USED "Usado en impresion"
|
||||
#define MSG_CURRENT "Actual"
|
||||
#define MSG_CHOOSE_EXTRUDER "Elegir extrusor:"
|
||||
#define MSG_EXTRUDER "Extrusor"
|
||||
#define MSG_EXTRUDER_1 "Extrusor 1"
|
||||
#define MSG_EXTRUDER_2 "Extrusor 2"
|
||||
#define MSG_EXTRUDER_3 "Extrusor 3"
|
||||
#define MSG_EXTRUDER_4 "Extrusor 4"
|
||||
|
||||
#define MSG_WIZARD "Wizard"
|
||||
#define MSG_WIZARD_WELCOME "Hola, soy tu impresora Original Prusa i3. Quieres que te guie a traves de la configuracion?"
|
||||
#define MSG_WIZARD_QUIT "Siempre puedes acceder al asistente desde Calibracion -> Wizard"
|
||||
#define MSG_WIZARD_SELFTEST "Primero, hare el Selftest para comprobar los problemas de montaje mas comunes."
|
||||
#define MSG_WIZARD_CALIBRATION_FAILED "Lee el manual y resuelve el problema. Despues, reinicia la impresora y continua con el Wizard"
|
||||
#define MSG_WIZARD_XYZ_CAL "Hare la calibracion XYZ. Tardara 12 min. aproximadamente."
|
||||
#define MSG_WIZARD_FILAMENT_LOADED "Esta el filamento cargado?"
|
||||
#define MSG_WIZARD_Z_CAL "Voy a hacer Calibracion Z ahora."
|
||||
#define MSG_WIZARD_WILL_PREHEAT "Voy a precalentar el nozzle para PLA ahora."
|
||||
#define MSG_WIZARD_V2_CAL "Voy a calibrar la distancia entre la punta del nozzle y la superficie de la heatbed."
|
||||
#define MSG_WIZARD_V2_CAL_2 "Voy a comenzar a imprimir la linea y tu bajaras el nozzle gradualmente al rotar el mando, hasta que llegues a la altura optima. Mira las imagenes del capitulo Calibracion en el manual."
|
||||
#define MSG_V2_CALIBRATION "Cal. primera cap."
|
||||
#define MSG_WIZARD_DONE "Terminado! Feliz impresion!"
|
||||
#define MSG_WIZARD_LOAD_FILAMENT "Inserta, por favor, filamento PLA en el extrusor. Despues haz clic para cargarlo."
|
||||
#define MSG_WIZARD_RERUN "Ejecutar el Wizard borrara los valores de calibracion actuales y comenzara de nuevo. Continuar?"
|
||||
#define MSG_WIZARD_REPEAT_V2_CAL "Quieres repetir el ultimo paso para reajustar la distancia nozzle-heatbed?"
|
||||
#define MSG_WIZARD_CLEAN_HEATBED "Limpia la superficie de la heatbed, por favor, y haz clic"
|
||||
#define MSG_WIZARD_PLA_FILAMENT "Es el filamento PLA?"
|
||||
#define MSG_WIZARD_INSERT_CORRECT_FILAMENT "Carga filamento PLA, por favor, y reinicia la impresora para continuar con el Wizard"
|
||||
#define MSG_PLA_FILAMENT_LOADED "Esta el filamento PLA cargado?"
|
||||
#define MSG_PLEASE_LOAD_PLA "Carga el filamento PLA primero por favor."
|
||||
#define MSG_WIZARD_HEATING "Precalentando nozzle. Espera por favor."
|
||||
#define MSG_M117_V2_CALIBRATION "M117 Cal. primera cap."
|
|
@ -1,275 +1,322 @@
|
|||
/**
|
||||
* Italian
|
||||
*
|
||||
* LCD Menu Messages
|
||||
* Please note these are limited to 17 characters!
|
||||
*
|
||||
*/
|
||||
#ifndef LANGUAGE_IT_H
|
||||
#define LANGUAGE_IT_H
|
||||
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " pronto."
|
||||
#define MSG_SD_INSERTED "SD Card inserita"
|
||||
#define MSG_SD_REMOVED "SD Card rimossa"
|
||||
#define MSG_MAIN "Menu principale"
|
||||
#define MSG_DISABLE_STEPPERS "Disabilita Motori"
|
||||
#define MSG_AUTO_HOME "Auto Home"
|
||||
#define MSG_COOLDOWN "Raffredda"
|
||||
#define MSG_MOVE_AXIS "Muovi Asse"
|
||||
#define MSG_MOVE_X "Muovi X"
|
||||
#define MSG_MOVE_Y "Muovi Y"
|
||||
#define MSG_MOVE_Z "Muovi Z"
|
||||
#define MSG_MOVE_E "Estrusore"
|
||||
#define MSG_SPEED "Velcità"
|
||||
#define MSG_NOZZLE "Ugello"
|
||||
#define MSG_BED "Piatto"
|
||||
#define MSG_FAN_SPEED "Ventola"
|
||||
#define MSG_FLOW "Flusso"
|
||||
#define MSG_TEMPERATURE "Temperatura"
|
||||
#define MSG_WATCH "Guarda"
|
||||
#define MSG_TUNE "Adatta"
|
||||
#define MSG_PAUSE_PRINT "Pausa"
|
||||
#define MSG_RESUME_PRINT "Riprendi stampa"
|
||||
#define MSG_STOP_PRINT "Arresta stampa"
|
||||
#define MSG_CARD_MENU "Menu SD Carta"
|
||||
#define MSG_NO_CARD "No SD Carta"
|
||||
#define MSG_DWELL "Sospensione..."
|
||||
#define MSG_USERWAIT "Attendi Utente..."
|
||||
#define MSG_RESUMING "Riprendi Stampa"
|
||||
#define MSG_PRINT_ABORTED "Stampa abortita"
|
||||
#define MSG_NO_MOVE "Nessun Movimento"
|
||||
#define MSG_KILLED "UCCISO "
|
||||
#define MSG_STOPPED "ARRESTATO "
|
||||
#define MSG_FILAMENTCHANGE "Cambiare filamento"
|
||||
#define MSG_BABYSTEP_Z "Babystep Z"
|
||||
#define MSG_ADJUSTZ "Auto regolare Z ?"
|
||||
#define MSG_PICK_Z "Vyberte vytisk"
|
||||
#define MSG_SETTINGS "Impostazioni"
|
||||
#define MSG_PREHEAT "Preriscalda"
|
||||
#define MSG_UNLOAD_FILAMENT "Scaricare fil."
|
||||
#define MSG_LOAD_FILAMENT "Caricare filamento"
|
||||
#define MSG_ERROR "ERROR:"
|
||||
#define MSG_PREHEAT_NOZZLE "Preris. ugello!"
|
||||
#define MSG_SUPPORT "Support"
|
||||
#define MSG_CORRECTLY "Cambiato corr.?"
|
||||
#define MSG_YES "Si"
|
||||
#define MSG_NO "No"
|
||||
#define MSG_NOT_LOADED "Fil. no cargado"
|
||||
#define MSG_NOT_COLOR "Color no claro"
|
||||
#define MSG_LOADING_FILAMENT "Cargando fil."
|
||||
#define MSG_PLEASE_WAIT "Aspetta"
|
||||
#define MSG_LOADING_COLOR "Cargando color"
|
||||
#define MSG_CHANGE_SUCCESS "Cambia. riuscito!"
|
||||
#define MSG_PRESS "Y pulse el mando"
|
||||
#define MSG_INSERT_FILAMENT "Inserire filamento"
|
||||
#define MSG_CHANGING_FILAMENT "Mutevole fil.!"
|
||||
#define MSG_SILENT_MODE_ON "Modo [silenzioso]"
|
||||
#define MSG_SILENT_MODE_OFF "Modo [piu forza]"
|
||||
#define MSG_REBOOT "Riavvio la stamp."
|
||||
#define MSG_TAKE_EFFECT " per mostrare i camb."
|
||||
#define MSG_HEATING "Riscaldamento..."
|
||||
#define MSG_HEATING_COMPLETE "Riscaldamento fatto."
|
||||
#define MSG_BED_HEATING "Piatto riscaldam."
|
||||
#define MSG_BED_DONE "Piatto fatto."
|
||||
#define MSG_LANGUAGE_NAME "Italiano"
|
||||
#define MSG_LANGUAGE_SELECT "Selez. la lingua"
|
||||
#define MSG_PRUSA3D "prusa3d.com"
|
||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
|
||||
|
||||
// Do not translate those!
|
||||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_EXTERNAL_RESET " External Reset"
|
||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
||||
#define MSG_AUTHOR " | Author: "
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
#define MSG_FILE_PRINTED "Done printing file"
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
#define MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
#define MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
#define MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_COUNT_X " Count X: "
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
#define MSG_X_MIN "x_min: "
|
||||
#define MSG_X_MAX "x_max: "
|
||||
#define MSG_Y_MIN "y_min: "
|
||||
#define MSG_Y_MAX "y_max: "
|
||||
#define MSG_Z_MIN "z_min: "
|
||||
#define MSG_Z_MAX "z_max: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
#define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
#define MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
#define MSG_SD_CARD_OK "SD card ok"
|
||||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_SIZE " Size: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
#define MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Adjusting Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
#define MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
#define MSG_SET_ORIGIN "Set origin"
|
||||
#define MSG_PREHEAT_PLA "Preheat PLA"
|
||||
#define MSG_PREHEAT_PLA0 "Preheat PLA 1"
|
||||
#define MSG_PREHEAT_PLA1 "Preheat PLA 2"
|
||||
#define MSG_PREHEAT_PLA2 "Preheat PLA 3"
|
||||
#define MSG_PREHEAT_PLA012 "Preheat PLA All"
|
||||
#define MSG_PREHEAT_PLA_BEDONLY "Preheat PLA Bed"
|
||||
#define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA conf"
|
||||
#define MSG_PREHEAT_ABS "Preheat ABS"
|
||||
#define MSG_PREHEAT_ABS0 "Preheat ABS 1"
|
||||
#define MSG_PREHEAT_ABS1 "Preheat ABS 2"
|
||||
#define MSG_PREHEAT_ABS2 "Preheat ABS 3"
|
||||
#define MSG_PREHEAT_ABS012 "Preheat ABS All"
|
||||
#define MSG_PREHEAT_ABS_BEDONLY "Preheat ABS Bed"
|
||||
#define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS conf"
|
||||
#define MSG_SWITCH_PS_ON "Switch power on"
|
||||
#define MSG_SWITCH_PS_OFF "Switch power off"
|
||||
#define MSG_AUTOTEMP "Autotemp"
|
||||
#define MSG_ON "On "
|
||||
#define MSG_OFF "Off"
|
||||
#define MSG_PID_P "PID-P"
|
||||
#define MSG_PID_I "PID-I"
|
||||
#define MSG_PID_D "PID-D"
|
||||
#define MSG_PID_C "PID-C"
|
||||
#define MSG_ACC "Accel"
|
||||
#define MSG_VXY_JERK "Vxy-jerk"
|
||||
#define MSG_VZ_JERK "Vz-jerk"
|
||||
#define MSG_VE_JERK "Ve-jerk"
|
||||
#define MSG_VMAX "Vmax "
|
||||
#define MSG_X "x"
|
||||
#define MSG_Y "y"
|
||||
#define MSG_Z "z"
|
||||
#define MSG_E "e"
|
||||
#define MSG_VMIN "Vmin"
|
||||
#define MSG_VTRAV_MIN "VTrav min"
|
||||
#define MSG_AMAX "Amax "
|
||||
#define MSG_A_RETRACT "A-retract"
|
||||
#define MSG_XSTEPS "Xsteps/mm"
|
||||
#define MSG_YSTEPS "Ysteps/mm"
|
||||
#define MSG_ZSTEPS "Zsteps/mm"
|
||||
#define MSG_ESTEPS "Esteps/mm"
|
||||
#define MSG_RETRACT "Retract"
|
||||
#define MSG_EXTRUDE "Extrude"
|
||||
#define MSG_AUTOSTART "Autostart"
|
||||
#define MSG_MOVE_E1 "Extruder2"
|
||||
#define MSG_MOVE_E2 "Extruder3"
|
||||
#define MSG_MOVE_01MM "Move 0.1mm"
|
||||
#define MSG_MOVE_1MM "Move 1mm"
|
||||
#define MSG_MOVE_10MM "Move 10mm"
|
||||
#define MSG_NOZZLE1 "Nozzle2"
|
||||
#define MSG_NOZZLE2 "Nozzle3"
|
||||
#define MSG_FLOW0 "Flow 0"
|
||||
#define MSG_FLOW1 "Flow 1"
|
||||
#define MSG_FLOW2 "Flow 2"
|
||||
#define MSG_CONTROL "Control"
|
||||
#define MSG_MIN " \002 Min"
|
||||
#define MSG_MAX " \002 Max"
|
||||
#define MSG_FACTOR " \002 Fact"
|
||||
#define MSG_MOTION "Motion"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
|
||||
#define MSG_CONTRAST "LCD contrast"
|
||||
#define MSG_STORE_EPROM "Store memory"
|
||||
#define MSG_LOAD_EPROM "Load memory"
|
||||
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
#define MSG_REFRESH "\xF8" "Refresh"
|
||||
#define MSG_PREPARE "Prepare"
|
||||
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
|
||||
#define MSG_CONTROL_RETRACTF "Retract V"
|
||||
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
|
||||
#define MSG_AUTORETRACT "AutoRetr."
|
||||
#define MSG_INIT_SDCARD "Init. SD card"
|
||||
#define MSG_CNG_SDCARD "Change SD card"
|
||||
#define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||
#define MSG_RECTRACT "Rectract"
|
||||
|
||||
#define MSG_HOMEYZ "Calibra Z"
|
||||
#define MSG_HOMEYZ_PROGRESS "Calibrando Z"
|
||||
#define MSG_HOMEYZ_DONE "Calibratura OK"
|
||||
|
||||
#define MSG_SELFTEST_ERROR "Autotest negativo"
|
||||
#define MSG_SELFTEST_PLEASECHECK "Verifica:"
|
||||
#define MSG_SELFTEST_NOTCONNECTED "Non connesso"
|
||||
#define MSG_SELFTEST_HEATERTHERMISTOR "Riscald./Termistore"
|
||||
#define MSG_SELFTEST_BEDHEATER "Piastra/Riscaldatore"
|
||||
#define MSG_SELFTEST_WIRINGERROR "Errore cablaggio"
|
||||
#define MSG_SELFTEST_ENDSTOPS "Limiti corsa"
|
||||
#define MSG_SELFTEST_MOTOR "Motore"
|
||||
#define MSG_SELFTEST_ENDSTOP "Limite corsa"
|
||||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Lim. fuoriportata"
|
||||
#define MSG_SELFTEST_OK "Autotest OK"
|
||||
|
||||
#define MSG_STATS_TOTALFILAMENT "Filamento tot:"
|
||||
#define MSG_STATS_TOTALPRINTTIME "Tempo stampa tot:"
|
||||
#define MSG_STATS_FILAMENTUSED "Filamento:"
|
||||
#define MSG_STATS_PRINTTIME "Tempo stampa:"
|
||||
|
||||
#define MSG_SELFTEST_START "Inizia autotest"
|
||||
#define MSG_SELFTEST_CHECK_ENDSTOPS "Verifica limiti"
|
||||
#define MSG_SELFTEST_CHECK_HOTEND "Verifica lim temp"
|
||||
#define MSG_SELFTEST_CHECK_X "Verifica asse X"
|
||||
#define MSG_SELFTEST_CHECK_Y "Verifica asse Y"
|
||||
#define MSG_SELFTEST_CHECK_Z "Verifica asse Z"
|
||||
#define MSG_SELFTEST_CHECK_BED "Verifica piastra"
|
||||
#define MSG_SELFTEST_CHECK_ALLCORRECT "Nessun errore"
|
||||
#define MSG_SELFTEST "Autotest"
|
||||
#define MSG_SELFTEST_FAILED "Autotest fallito"
|
||||
|
||||
#define MSG_STATISTICS "Statistiche"
|
||||
#define MSG_USB_PRINTING "Stampa da USB"
|
||||
|
||||
|
||||
#endif // LANGUAGE_EN_H
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " pronta."
|
||||
#define MSG_SD_INSERTED "SD inserita"
|
||||
#define MSG_SD_REMOVED "SD rimossa"
|
||||
#define MSG_MAIN "Menu principale"
|
||||
#define MSG_DISABLE_STEPPERS "Disabilit motori"
|
||||
#define MSG_AUTO_HOME "Trova origine"
|
||||
#define MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
#define MSG_SET_ORIGIN "Set origin"
|
||||
#define MSG_COOLDOWN "Raffredda"
|
||||
#define MSG_SWITCH_PS_ON "Switch power on"
|
||||
#define MSG_SWITCH_PS_OFF "Switch power off"
|
||||
#define MSG_MOVE_AXIS "Muovi asse"
|
||||
#define MSG_MOVE_X "Muovi X"
|
||||
#define MSG_MOVE_Y "Muovi Y"
|
||||
#define MSG_MOVE_Z "Muovi Z"
|
||||
#define MSG_MOVE_E "Muovi Estrusore"
|
||||
#define MSG_MOVE_01MM "Move 0.1mm"
|
||||
#define MSG_MOVE_1MM "Move 1mm"
|
||||
#define MSG_MOVE_10MM "Move 10mm"
|
||||
#define MSG_SPEED "Velocita"
|
||||
#define MSG_NOZZLE "Ugello"
|
||||
#define MSG_NOZZLE1 "Nozzle2"
|
||||
#define MSG_NOZZLE2 "Nozzle3"
|
||||
#define MSG_BED "Letto"
|
||||
#define MSG_FAN_SPEED "Velocita vent."
|
||||
#define MSG_FLOW "Flusso"
|
||||
#define MSG_TEMPERATURE "Temperatura"
|
||||
#define MSG_MOTION "Motion"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_STORE_EPROM "Store memory"
|
||||
#define MSG_LOAD_EPROM "Load memory"
|
||||
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
#define MSG_REFRESH "\xF8" "Refresh"
|
||||
#define MSG_WATCH "Schermata info"
|
||||
#define MSG_TUNE "Regola"
|
||||
#define MSG_PAUSE_PRINT "Metti in pausa"
|
||||
#define MSG_RESUME_PRINT "Riprendi stampa"
|
||||
#define MSG_STOP_PRINT "Arresta stampa"
|
||||
#define MSG_CARD_MENU "Stampa da SD"
|
||||
#define MSG_NO_CARD "Nessuna SD"
|
||||
#define MSG_DWELL "Sospensione..."
|
||||
#define MSG_USERWAIT "Attendendo utente"
|
||||
#define MSG_RESUMING "Riprendi stampa"
|
||||
#define MSG_PRINT_ABORTED "Stampa abortita"
|
||||
#define MSG_NO_MOVE "Nessun movimento."
|
||||
#define MSG_KILLED "IN TILT."
|
||||
#define MSG_STOPPED "ARRESTATO."
|
||||
#define MSG_FILAMENTCHANGE "Camb. filamento"
|
||||
#define MSG_INIT_SDCARD "Init. SD card"
|
||||
#define MSG_CNG_SDCARD "Change SD card"
|
||||
#define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
#define MSG_BABYSTEP_Z "Compensazione Z"
|
||||
#define MSG_ADJUSTZ "Autoregolare Z?"
|
||||
#define MSG_PICK_Z "Pick print"
|
||||
|
||||
#define MSG_SETTINGS "Impostazioni"
|
||||
#define MSG_PREHEAT "Preriscalda"
|
||||
#define MSG_HEATING "Riscaldamento..."
|
||||
#define MSG_SUPPORT "Support"
|
||||
#define MSG_YES "Si"
|
||||
#define MSG_NO "No"
|
||||
#define MSG_NOT_LOADED "Fil. non caricato"
|
||||
#define MSG_NOT_COLOR "Colore non puro"
|
||||
#define MSG_LOADING_COLOR "Caricando colore"
|
||||
#define MSG_CHANGE_SUCCESS "Cambio riuscito!"
|
||||
#define MSG_PRESS "e cliccare manopola"
|
||||
#define MSG_INSERT_FILAMENT "Inserire filamento"
|
||||
#define MSG_CHANGING_FILAMENT "Cambiando filam."
|
||||
|
||||
#define MSG_PLEASE_WAIT "Aspetta"
|
||||
#define MSG_PREHEAT_NOZZLE "Preris. ugello!"
|
||||
#define MSG_HEATING_COMPLETE "Riscald. completo"
|
||||
#define MSG_BED_HEATING "Riscald. letto"
|
||||
#define MSG_BED_DONE "Piatto fatto."
|
||||
#define MSG_ERROR "ERRORE:"
|
||||
#define MSG_CORRECTLY "Cambiato corr.?"
|
||||
#define MSG_LOADING_FILAMENT "Caricando filam."
|
||||
#define MSG_UNLOAD_FILAMENT "Scarica filamento"
|
||||
#define MSG_LOAD_FILAMENT "Carica filamento"
|
||||
|
||||
#define MSG_SILENT_MODE_ON "Modo [silenzioso]"
|
||||
#define MSG_SILENT_MODE_OFF "Mode [forte]"
|
||||
#define MSG_REBOOT "Riavvia stampante"
|
||||
#define MSG_TAKE_EFFECT " per attualizzare"
|
||||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
#define MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
#define MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
#define MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
#define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
#define MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
#define MSG_SD_CARD_OK "SD card ok"
|
||||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
#define MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Compensazione Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
|
||||
#define MSG_LANGUAGE_NAME "Italiano"
|
||||
#define MSG_LANGUAGE_SELECT "Seleziona lingua"
|
||||
#define MSG_PRUSA3D "prusa3d.com"
|
||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
|
||||
#define MSG_SELFTEST_ERROR "Autotest negativo"
|
||||
#define MSG_SELFTEST_PLEASECHECK "Verificare:"
|
||||
#define MSG_SELFTEST_NOTCONNECTED "Non connesso"
|
||||
#define MSG_SELFTEST_HEATERTHERMISTOR "Riscald./Termist."
|
||||
#define MSG_SELFTEST_BEDHEATER "Letto/Riscald."
|
||||
#define MSG_SELFTEST_WIRINGERROR "Errore cablaggio"
|
||||
#define MSG_SELFTEST_ENDSTOPS "Finecorsa (2)"
|
||||
#define MSG_SELFTEST_MOTOR "Motore"
|
||||
#define MSG_SELFTEST_ENDSTOP "Finecorsa"
|
||||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Finec. fuori por."
|
||||
#define MSG_SELFTEST_OK "Autotest OK"
|
||||
|
||||
#define MSG_SELFTEST_FAN "Prova del ventilator"
|
||||
#define MSG_SELFTEST_COOLING_FAN "Vent di stampa ant.?"
|
||||
#define MSG_SELFTEST_EXTRUDER_FAN "Vent SX sull'ugello?"
|
||||
#define MSG_SELFTEST_FAN_YES "Gira"
|
||||
#define MSG_SELFTEST_FAN_NO "Non si gira"
|
||||
|
||||
#define MSG_STATS_TOTALFILAMENT "Filamento tot:"
|
||||
#define MSG_STATS_TOTALPRINTTIME "Tempo stampa tot:"
|
||||
#define MSG_STATS_FILAMENTUSED "Filamento usato:"
|
||||
#define MSG_STATS_PRINTTIME "Tempo di stampa:"
|
||||
#define MSG_SELFTEST_START "Avvia autotest"
|
||||
#define MSG_SELFTEST_CHECK_ENDSTOPS "Verifica finecorsa"
|
||||
#define MSG_SELFTEST_CHECK_HOTEND "Verifica ugello"
|
||||
#define MSG_SELFTEST_CHECK_X "Verifica asse X"
|
||||
#define MSG_SELFTEST_CHECK_Y "Verifica asse Y"
|
||||
#define MSG_SELFTEST_CHECK_Z "Verifica asse Z"
|
||||
#define MSG_SELFTEST_CHECK_BED "Verifica letto"
|
||||
#define MSG_SELFTEST_CHECK_ALLCORRECT "Nessun errore"
|
||||
#define MSG_SELFTEST "Autotest"
|
||||
#define MSG_SELFTEST_FAILED "Autotest fallito"
|
||||
#define MSG_STATISTICS "Statistiche"
|
||||
#define MSG_USB_PRINTING "Stampa da USB"
|
||||
#define MSG_HOMEYZ "Calibra Z"
|
||||
#define MSG_HOMEYZ_PROGRESS "Calibrando Z"
|
||||
#define MSG_HOMEYZ_DONE "Calibrazione OK"
|
||||
|
||||
|
||||
|
||||
#define MSG_SHOW_END_STOPS "Stato finecorsa"
|
||||
#define MSG_CALIBRATE_BED "Calibra XYZ"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset XYZ calibr."
|
||||
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP "Calibrazione XYZ. Ruotare la manopola per alzare il carrello Z fino all'altezza massima. Click per terminare."
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Calibrazione Z. Ruotare la manopola per alzare il carrello Z fino all'altezza massima. Click per terminare."
|
||||
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN "Pulire l'ugello per la calibrazione, poi fare click."
|
||||
#define MSG_CONFIRM_CARRIAGE_AT_THE_TOP "I carrelli Z sin/des sono altezza max?"
|
||||
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Ricerca del letto punto di calibraz."
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " su 4"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Perfezion. il letto punto di calibraz."
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " su 4"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Misurare l'altezza di riferimento del punto di calibrazione"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " su 9"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Reiterazione "
|
||||
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Calibrazione XYZ fallita. Il punto di calibrazione sul letto non e' stato trovato."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Calibrazione XYZ fallita. Si prega di consultare il manuale."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Calibrazione XYZ OK. Gli assi X/Y sono perpendicolari. Complimenti!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Calibrazion XYZ corretta. Assi X/Y leggermente storti. Ben fatto!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Calibrazion XYZ corretta. La distorsione verra' automaticamente compensata."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Calibrazione XYZ fallita. Punto anteriore sinistro non raggiungibile."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Calibrazione XYZ fallita. Punto anteriore destro non raggiungibile."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Calibrazione XYZ fallita. Punti anteriori non raggiungibili."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Calibrazione XYZ compromessa. Punto anteriore sinistro non raggiungibile."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Calibrazione XYZ compromessa. Punto anteriore destro non raggiungibile."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Calibrazione XYZ compromessa. Punti anteriori non raggiungibili."
|
||||
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_LOW "Livellamento letto fallito.NoRispSensor Residui su ugello? In attesa di reset."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_HIGH "Livellamento letto fallito.Risp sensore troppo prestoIn attesa di reset."
|
||||
#define MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Livellamento letto fallito. Sensore discon. o Cavo Dann. In attesa di reset."
|
||||
|
||||
#define MSG_NEW_FIRMWARE_AVAILABLE "Nuova versione del firmware disponibile"
|
||||
#define MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Prega aggiorna."
|
||||
|
||||
#define MSG_FOLLOW_CALIBRATION_FLOW "Stampante ancora non calibrata. Si prega di seguire il manuale, capitolo PRIMI PASSI, sezione della calibrazione."
|
||||
#define MSG_BABYSTEP_Z_NOT_SET "Distanza tra la punta dell'ugello e la superficie del letto non ancora imposta. Si prega di seguire il manuale, capitolo First steps, sezione First layer calibration."
|
||||
|
||||
#define MSG_BED_CORRECTION_MENU "Correz. liv.letto"
|
||||
#define MSG_BED_CORRECTION_LEFT "Sinistra [um]"
|
||||
#define MSG_BED_CORRECTION_RIGHT "Destra [um]"
|
||||
#define MSG_BED_CORRECTION_FRONT "Fronte [um]"
|
||||
#define MSG_BED_CORRECTION_REAR "Retro [um]"
|
||||
#define MSG_BED_CORRECTION_RESET "Reset"
|
||||
|
||||
#define MSG_MESH_BED_LEVELING "Mesh livel. letto"
|
||||
#define MSG_MENU_CALIBRATION "Calibrazione"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
|
||||
#define MSG_LOOSE_PULLEY "Puleggia lenta"
|
||||
#define MSG_FILAMENT_LOADING_T0 "Inserire filamento nell'estrusore 1. Click per continuare."
|
||||
#define MSG_FILAMENT_LOADING_T1 "Inserire filamento nell'estrusore 2. Click per continuare."
|
||||
#define MSG_FILAMENT_LOADING_T2 "Inserire filamento nell'estrusore 3. Click per continuare."
|
||||
#define MSG_FILAMENT_LOADING_T3 "Inserire filamento nell'estrusore 4. Click per continuare."
|
||||
#define MSG_CHANGE_EXTR "Cambio estrusore."
|
||||
|
||||
#define MSG_FIL_ADJUSTING "Filamento in fase di regolazione. Attendere prego."
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "I filamenti sono regolati. Si prega di pulire l'ugello per la calibrazione. Click per continuare."
|
||||
#define MSG_CALIBRATE_E "Calibra E"
|
||||
#define MSG_E_CAL_KNOB "Girare la manopola affinche' il segno raggiunga il corpo dell'estrusore. Click per continuare."
|
||||
#define MSG_MARK_FIL "Segnare il filamento a 100 mm di distanza dal corpo dell'estrusore. Click per continuare."
|
||||
#define MSG_CLEAN_NOZZLE_E "Calibrazione E terminata. Si prega di pulire l'ugello. Click per continuare."
|
||||
#define MSG_WAITING_TEMP "In attesa del raffreddamento della testina e del piatto"
|
||||
#define MSG_FILAMENT_CLEAN "Il colore e' nitido?"
|
||||
#define MSG_UNLOADING_FILAMENT "Rilasc. filamento"
|
||||
#define MSG_PAPER "Porre un foglio sotto l'ugello durante la calibrazione dei primi 4 punti. In caso l'ugello muova il foglio spegnere prontamente la stampante."
|
||||
|
||||
#define MSG_FINISHING_MOVEMENTS "Arresto in corso"
|
||||
#define MSG_PRINT_PAUSED "Stampa in pausa"
|
||||
#define MSG_RESUMING_PRINT "Stampa in ripresa"
|
||||
#define MSG_PID_EXTRUDER "Calibrazione PID"
|
||||
#define MSG_SET_TEMPERATURE "Imposta temperatura"
|
||||
#define MSG_PID_FINISHED "Cal. PID completa"
|
||||
#define MSG_PID_RUNNING "Cal. PID"
|
||||
|
||||
#define MSG_CALIBRATE_PINDA "Calibrare"
|
||||
#define MSG_CALIBRATION_PINDA_MENU "Taratura temp."
|
||||
#define MSG_PINDA_NOT_CALIBRATED "Taratura della temperatura non ancora eseguita"
|
||||
#define MSG_PINDA_PREHEAT "Riscald. PINDA"
|
||||
#define MSG_TEMP_CALIBRATION "Cal. temp. "
|
||||
#define MSG_TEMP_CALIBRATION_DONE "Taratura temperatura terminata. Fare click per continuare."
|
||||
#define MSG_TEMP_CALIBRATION_ON "Cal. temp. [ON]"
|
||||
#define MSG_TEMP_CALIBRATION_OFF "Cal. temp. [OFF]"
|
||||
|
||||
#define MSG_LOAD_ALL "Caricare tutti"
|
||||
#define MSG_LOAD_FILAMENT_1 "Caricare fil. 1"
|
||||
#define MSG_LOAD_FILAMENT_2 "Caricare fil. 2"
|
||||
#define MSG_LOAD_FILAMENT_3 "Caricare fil. 3"
|
||||
#define MSG_LOAD_FILAMENT_4 "Caricare fil. 4"
|
||||
#define MSG_UNLOAD_FILAMENT_1 "Rilasciare fil. 1"
|
||||
#define MSG_UNLOAD_FILAMENT_2 "Rilasciare fil. 1"
|
||||
#define MSG_UNLOAD_FILAMENT_3 "Rilasciare fil. 1"
|
||||
#define MSG_UNLOAD_FILAMENT_4 "Rilasciare fil. 1"
|
||||
#define MSG_UNLOAD_ALL "Rilasciare tutti"
|
||||
#define MSG_PREPARE_FILAMENT "Preparare filamento"
|
||||
#define MSG_ALL "Tutti"
|
||||
#define MSG_USED "Usati nella stampa"
|
||||
#define MSG_CURRENT "Attuale"
|
||||
#define MSG_CHOOSE_EXTRUDER "Seleziona estrusore:"
|
||||
#define MSG_EXTRUDER "Estrusore"
|
||||
#define MSG_EXTRUDER_1 "Estrusore 1"
|
||||
#define MSG_EXTRUDER_2 "Estrusore 2"
|
||||
#define MSG_EXTRUDER_3 "Estrusore 3"
|
||||
#define MSG_EXTRUDER_4 "Estrusore 4"
|
||||
|
||||
#define MSG_WIZARD "Wizard"
|
||||
#define MSG_WIZARD_WELCOME "Ciao, sono la tua stampante Original Prusa i3. Gradiresti aiuto attraverso il processo di configurazione?"
|
||||
#define MSG_WIZARD_QUIT "E possibile proseguire la guide Wizard in qualsiasi momento attraverso Calibrazione -> Wizard."
|
||||
#define MSG_WIZARD_SELFTEST "Anzitutto avviero il Self Test per controllare gli errori di assemblaggio piu comuni."
|
||||
#define MSG_WIZARD_CALIBRATION_FAILED "Per favore consulta il nostro manuale per risolvere il problema. Poi riprendi il Wizard dopo aver riavviato la stampante."
|
||||
#define MSG_WIZARD_XYZ_CAL "Adesso avviero una Calibrazione XYZ. Puo durare circa 12 min."
|
||||
#define MSG_WIZARD_FILAMENT_LOADED "Il filamento e stato caricato?"
|
||||
#define MSG_WIZARD_Z_CAL "Adesso avviero una Calibrazione Z."
|
||||
#define MSG_WIZARD_WILL_PREHEAT "Adesso preriscaldero l'ugello per PLA."
|
||||
#define MSG_WIZARD_V2_CAL "Adesso tarero lo stacco fra ugello e superfice del piatto."
|
||||
#define MSG_WIZARD_V2_CAL_2 "Adesso iniziero a stampare una linea e tu dovrai abbassare l'ugello poco per volta ruotando la manopola sino a raggiungere una altezza ottimale. Per favore dai uno sguardo all'immagine del nostro manuale, cap.Calibrazione."
|
||||
#define MSG_V2_CALIBRATION "Cal. primo layer."
|
||||
#define MSG_WIZARD_DONE "Ben fatto. Buona stampa!"
|
||||
#define MSG_WIZARD_LOAD_FILAMENT "Per favore inserisci il filamento di PLA nell'estrusore, poi premi la manopola per caricare."
|
||||
#define MSG_WIZARD_RERUN "Se avvi il Wizard perderai la calibrazione preesistente e dovrai ricominciare dall'inizio. Continuare?"
|
||||
#define MSG_WIZARD_REPEAT_V2_CAL "Desideri ripetere l'ultimo passaggio per migliorare la distanza fra ugello e piatto?"
|
||||
#define MSG_WIZARD_CLEAN_HEATBED "Per favore pulisci il piatto, poi premi la manopola."
|
||||
#define MSG_WIZARD_PLA_FILAMENT "E questo un filamento di PLA?"
|
||||
#define MSG_WIZARD_INSERT_CORRECT_FILAMENT "Per favore carica filamento di PLA e riprendi il Wizard dopo aver riavviato la stampante."
|
||||
#define MSG_PLA_FILAMENT_LOADED "Il PLA e stato caricato?"
|
||||
#define MSG_PLEASE_LOAD_PLA "Per favore prima caricare filamento di PLA."
|
||||
#define MSG_WIZARD_HEATING "Sto preriscaldando l'ugello. Per favore attendi."
|
||||
#define MSG_M117_V2_CALIBRATION "M117 Cal. primo layer."
|
||||
|
||||
#define MSG_DATE "Data"
|
||||
#define MSG_XYZ_DETAILS "XYZ Cal. dettagli"
|
||||
#define MSG_Y_DISTANCE_FROM_MIN "Distanza Y da min:"
|
||||
#define MSG_LEFT "Sinistra:"
|
||||
#define MSG_RIGHT "Destra:"
|
||||
#define MSG_MEASURED_SKEW "Incl. misurata:"
|
||||
#define MSG_SLIGHT_SKEW "Incl. leggera:"
|
||||
#define MSG_SEVERE_SKEW "Inc. rilevante:"
|
|
@ -5,8 +5,6 @@
|
|||
* Please note these are limited to 17 characters!
|
||||
*
|
||||
*/
|
||||
#ifndef LANGUAGE_PL_H
|
||||
#define LANGUAGE_PL_H
|
||||
|
||||
#define WELCOME_MSG CUSTOM_MENDEL_NAME " gotowa"
|
||||
#define MSG_SD_INSERTED "Karta wlozona"
|
||||
|
@ -63,16 +61,17 @@
|
|||
#define MSG_PRESS "Nacisnij przycisk"
|
||||
#define MSG_INSERT_FILAMENT "Wprowadz filament"
|
||||
#define MSG_CHANGING_FILAMENT "Wymiana filamentu"
|
||||
#define MSG_SILENT_MODE_ON "Mod [cichy]"
|
||||
#define MSG_SILENT_MODE_OFF "Mod [w wydajnosc]"
|
||||
#define MSG_SILENT_MODE_ON "Tryb [cichy]"
|
||||
#define MSG_SILENT_MODE_OFF "Tryb[w wydajnosc]"
|
||||
|
||||
#define MSG_REBOOT "Restart drukarki"
|
||||
#define MSG_TAKE_EFFECT "wprow. zmian"
|
||||
#define MSG_TAKE_EFFECT " wprow. zmian"
|
||||
#define MSG_HEATING "Grzanie..."
|
||||
#define MSG_HEATING_COMPLETE "Grzanie OK."
|
||||
#define MSG_BED_HEATING "Grzanie stolika.."
|
||||
#define MSG_BED_DONE "Stolik OK."
|
||||
#define MSG_LANGUAGE_NAME "Polski"
|
||||
#define MSG_LANGUAGE_SELECT "Wybor jezyka "
|
||||
#define MSG_LANGUAGE_SELECT "Wybor jezyka"
|
||||
#define MSG_PRUSA3D "prusa3d.cz"
|
||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.cz"
|
||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.cz"
|
||||
|
@ -82,21 +81,12 @@
|
|||
|
||||
#define MSG_Enqueing "enqueing \""
|
||||
#define MSG_POWERUP "PowerUp"
|
||||
#define MSG_EXTERNAL_RESET " External Reset"
|
||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
||||
#define MSG_AUTHOR " | Author: "
|
||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
||||
#define MSG_FREE_MEMORY " Free Memory: "
|
||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
#define MSG_OK "ok"
|
||||
#define MSG_FILE_SAVED "Done saving file."
|
||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
||||
#define MSG_FILE_PRINTED "Done printing file"
|
||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
#define MSG_END_FILE_LIST "End file list"
|
||||
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
|
@ -107,23 +97,12 @@
|
|||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||
#define MSG_COUNT_X " Count X: "
|
||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
#define MSG_RESEND "Resend: "
|
||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
||||
#define MSG_X_MIN "x_min: "
|
||||
#define MSG_X_MAX "x_max: "
|
||||
#define MSG_Y_MIN "y_min: "
|
||||
#define MSG_Y_MAX "y_max: "
|
||||
#define MSG_Z_MIN "z_min: "
|
||||
#define MSG_Z_MAX "z_max: "
|
||||
#define MSG_M119_REPORT "Reporting endstop status"
|
||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
#define MSG_ENDSTOP_OPEN "open"
|
||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
||||
#define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
|
@ -132,7 +111,6 @@
|
|||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define MSG_SD_FILE_OPENED "File opened: "
|
||||
#define MSG_SD_SIZE " Size: "
|
||||
#define MSG_SD_FILE_SELECTED "File selected"
|
||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
|
@ -142,71 +120,17 @@
|
|||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
#define MSG_BABYSTEPPING_Z "Dostavovani Z"
|
||||
#define MSG_BABYSTEPPING_Z "Dostrojenie Z"
|
||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
#define MSG_SET_HOME_OFFSETS "Nastav pocatek home"
|
||||
#define MSG_SET_ORIGIN "Nastav pocatek"
|
||||
#define MSG_PREHEAT_PLA "Predehrev PLA"
|
||||
#define MSG_PREHEAT_PLA0 "Predehrev PLA 1"
|
||||
#define MSG_PREHEAT_PLA1 "Predehrev PLA 2"
|
||||
#define MSG_PREHEAT_PLA2 "Predehrev PLA 3"
|
||||
#define MSG_PREHEAT_PLA012 "Predehrev PLA All"
|
||||
#define MSG_PREHEAT_PLA_BEDONLY "Predehrev PLA Bed"
|
||||
#define MSG_PREHEAT_PLA_SETTINGS "Predehrev PLA conf"
|
||||
#define MSG_PREHEAT_ABS "Predehrev ABS"
|
||||
#define MSG_PREHEAT_ABS0 "Predehrev ABS 1"
|
||||
#define MSG_PREHEAT_ABS1 "Predehrev ABS 2"
|
||||
#define MSG_PREHEAT_ABS2 "Predehrev ABS 3"
|
||||
#define MSG_PREHEAT_ABS012 "Predehrev ABS All"
|
||||
#define MSG_PREHEAT_ABS_BEDONLY "Predehrev ABS Bed"
|
||||
#define MSG_PREHEAT_ABS_SETTINGS "Predehrev ABS conf"
|
||||
|
||||
#define MSG_SWITCH_PS_ON "Vypnout zdroj"
|
||||
#define MSG_SWITCH_PS_OFF "Zapnout zdroj"
|
||||
|
||||
#define MSG_AUTOTEMP "Autotemp"
|
||||
#define MSG_ON "On "
|
||||
#define MSG_OFF "Off"
|
||||
#define MSG_PID_P "PID-P"
|
||||
#define MSG_PID_I "PID-I"
|
||||
#define MSG_PID_D "PID-D"
|
||||
#define MSG_PID_C "PID-C"
|
||||
#define MSG_ACC "Accel"
|
||||
#define MSG_VXY_JERK "Vxy-jerk"
|
||||
#define MSG_VZ_JERK "Vz-jerk"
|
||||
#define MSG_VE_JERK "Ve-jerk"
|
||||
#define MSG_VMAX "Vmax "
|
||||
#define MSG_X "x"
|
||||
#define MSG_Y "y"
|
||||
#define MSG_Z "z"
|
||||
#define MSG_E "e"
|
||||
#define MSG_VMIN "Vmin"
|
||||
#define MSG_VTRAV_MIN "VTrav min"
|
||||
#define MSG_AMAX "Amax "
|
||||
#define MSG_A_RETRACT "A-retract"
|
||||
#define MSG_XSTEPS "Xsteps/mm"
|
||||
#define MSG_YSTEPS "Ysteps/mm"
|
||||
#define MSG_ZSTEPS "Zsteps/mm"
|
||||
#define MSG_ESTEPS "Esteps/mm"
|
||||
|
||||
#define MSG_RETRACT "Retract"
|
||||
|
||||
#define MSG_EXTRUDE "Extrudovat"
|
||||
|
||||
#define MSG_AUTOSTART "Autostart"
|
||||
|
||||
|
||||
#define MSG_MOVE_E1 "Extruder2"
|
||||
#define MSG_MOVE_E2 "Extruder3"
|
||||
|
||||
#define MSG_MOVE_01MM "Posunout o 0.1mm"
|
||||
#define MSG_MOVE_1MM "Posunout o 1mm"
|
||||
#define MSG_MOVE_10MM "Posunout o 10mm"
|
||||
|
||||
#define MSG_NOZZLE1 "Tryska2"
|
||||
#define MSG_NOZZLE1 "Tryska2"
|
||||
#define MSG_NOZZLE2 "Tryska3"
|
||||
|
||||
|
||||
|
@ -221,36 +145,16 @@
|
|||
#define MSG_MOTION "Pohyb"
|
||||
#define MSG_VOLUMETRIC "Filament"
|
||||
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
|
||||
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
|
||||
#define MSG_CONTRAST "LCD contrast"
|
||||
#define MSG_STORE_EPROM "Store memory"
|
||||
#define MSG_LOAD_EPROM "Ulozit pamet"
|
||||
#define MSG_RESTORE_FAILSAFE "Obnovit vychozi"
|
||||
#define MSG_REFRESH "\xF8" "Obnovit"
|
||||
|
||||
#define MSG_PREPARE "Priprava"
|
||||
|
||||
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
|
||||
#define MSG_CONTROL_RETRACTF "Retract V"
|
||||
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
|
||||
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
|
||||
#define MSG_AUTORETRACT "AutoRetr."
|
||||
|
||||
#define MSG_INIT_SDCARD "Inic. SD"
|
||||
#define MSG_INIT_SDCARD "Inic. SD"
|
||||
#define MSG_CNG_SDCARD "Vymenit SD"
|
||||
#define MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
#define MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
#define MSG_BABYSTEP_X "Babystep X"
|
||||
#define MSG_BABYSTEP_Y "Babystep Y"
|
||||
|
||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||
|
||||
#define MSG_RECTRACT "Rectract"
|
||||
|
||||
#define MSG_HOMEYZ "Kalibruj Z"
|
||||
|
@ -269,6 +173,12 @@
|
|||
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||
#define MSG_SELFTEST_OK "Self test OK"
|
||||
|
||||
#define MSG_SELFTEST_FAN "Test wentylatora"
|
||||
#define MSG_SELFTEST_COOLING_FAN "Przedni went. druku?"
|
||||
#define MSG_SELFTEST_EXTRUDER_FAN "Lewy went na dysze?"
|
||||
#define MSG_SELFTEST_FAN_YES "Kreci sie"
|
||||
#define MSG_SELFTEST_FAN_NO "Nie kreci sie"
|
||||
|
||||
#define MSG_STATS_TOTALFILAMENT "Filament lacznie :"
|
||||
#define MSG_STATS_TOTALPRINTTIME "Czas calkowity :"
|
||||
#define MSG_STATS_FILAMENTUSED "Filament : "
|
||||
|
@ -288,5 +198,138 @@
|
|||
#define MSG_STATISTICS "Statystyka "
|
||||
#define MSG_USB_PRINTING "Druk z USB "
|
||||
|
||||
#define MSG_SHOW_END_STOPS "Pokaz krancowki"
|
||||
#define MSG_CALIBRATE_BED "Kalibracja XYZ"
|
||||
#define MSG_CALIBRATE_BED_RESET "Reset kalibr. XYZ"
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibracja XYZ. Przekrec galke, aby przesunac os Z do gornych krancowek. Nacisnij, by potwierdzic."
|
||||
#define MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Kalibracja Z. Przekrec galke, aby przesunac os Z do gornych krancowek. Nacisnij, by potwierdzic."
|
||||
|
||||
#endif // LANGUAGE_EN_H
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN "Dla prawidl. kalibracji prosze oczyscic dysze. Potw. guzikiem."
|
||||
#define MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Oba wozki dojechaly do gornej ramy?"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Szukam punktu kalibracyjnego podkladki"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Poprawiam precyzyjnosc punktu kalibracyjnego"
|
||||
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Okreslam wysokosc odniesienia punktu kalibracyjnego"
|
||||
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " z 9"
|
||||
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteracja "
|
||||
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibr. XYZ nieudana. Kalibracyjny punkt podkladki nieznaleziony."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibracja XYZ niepowiedziona. Sprawdzic w instrukcji."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Kalibracja XYZ ok. Osie X/Y sa prostopadle. Gratulacje!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Kalibracja XYZ prawidlowa. Osie X/Y lekko skosne. Dobra robota!"
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Kalibracja XYZ prawidlowa. Skosy beda automatycznie wyrownane przy druku."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Kalibr. XYZ nieudana. Lewy przedni punkt zbyt do przodu. Wyrownac drukarke."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Kalibr. XYZ nieudana. Prawy przedni punkt zbyt do przodu. Wyrownac drukarke."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Kalibr. XYZ nieudana. Przed. punkty kalibr. zbyt do przodu. Wyrownac drukarke."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Kalibracja XYZ niedokladna. Lewy przedni punkt zbyt wysuniety do przodu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Kalibracja XYZ niedokladna. Prawy przedni punkt zbyt wysuniety do przodu."
|
||||
#define MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Kalibr. XYZ niedokladna. Przednie punkty kalibr. Zbyt wys. do przodu."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_LOW "Kalibracja nieudana. Sensor nie dotknal. Zanieczysz. dysza? Czekam na reset."
|
||||
#define MSG_BED_LEVELING_FAILED_POINT_HIGH "Kalibracja Z nieudana. Sensor dotk. za wysoko. Czekam na reset."
|
||||
#define MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Kalibracja nieudana. Sensor odlaczony lub uszkodz. kabel. Czekam na reset."
|
||||
#define MSG_NEW_FIRMWARE_AVAILABLE "Wyszla nowa wersja firmware:"
|
||||
#define MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Prosze zaktualizowac"
|
||||
#define MSG_FOLLOW_CALIBRATION_FLOW "Drukarka nie zostala jeszcze skalibrowana. Prosze kierowac sie instrukcja, rozdzial Zaczynamy, podrozdzial Selftest."
|
||||
#define MSG_BABYSTEP_Z_NOT_SET "Odleglosc dyszy od podkladki nie jest skalibrowana. Postepuj zgodnie z instrukcja rozdzial Zaczynamy, podrozdzial Kalibracja pierwszej warstwy."
|
||||
#define MSG_BED_CORRECTION_MENU "Korekta podkladki"
|
||||
#define MSG_BED_CORRECTION_LEFT "W lewo [um]"
|
||||
#define MSG_BED_CORRECTION_RIGHT "W prawo [um]"
|
||||
#define MSG_BED_CORRECTION_FRONT "Do przodu [um]"
|
||||
#define MSG_BED_CORRECTION_REAR "Do tylu [um]"
|
||||
#define MSG_BED_CORRECTION_RESET "Reset"
|
||||
|
||||
#define MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
#define MSG_MENU_CALIBRATION "Kalibracja"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "karta SD [normal]"
|
||||
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "karta SD[FlshAir]"
|
||||
|
||||
#define MSG_LOOSE_PULLEY "Kolo pasowe"
|
||||
#define MSG_FILAMENT_LOADING_T0 "Wloz filament do ekstrudera 1. Potwierdz przyciskiem."
|
||||
#define MSG_FILAMENT_LOADING_T1 "Wloz filament do ekstrudera 2. Potwierdz przyciskiem."
|
||||
#define MSG_FILAMENT_LOADING_T2 "Wloz filament do ekstrudera 3. Potwierdz przyciskiem."
|
||||
#define MSG_FILAMENT_LOADING_T3 "Wloz filament do ekstrudera 4. Potwierdz przyciskiem."
|
||||
#define MSG_CHANGE_EXTR "Zmienic ekstruder"
|
||||
|
||||
#define MSG_FIL_ADJUSTING "Przebiega wyrownanie filamentow. Prosze czekac."
|
||||
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Dla prawidlowej kalibracji prosze oczyscic dysze. Potem potwierdzic przyciskiem."
|
||||
#define MSG_CALIBRATE_E "Kalibruj E"
|
||||
#define MSG_E_CAL_KNOB "Prosze otaczac przycisk poki znacznik nie dosiegnie ciala ekstrudera. Potwierdzic przyciskiem."
|
||||
#define MSG_MARK_FIL "Prosze oznaczyc filament 100 mm od ciala ekstrudera. Potwierdzic przyciskiem."
|
||||
#define MSG_CLEAN_NOZZLE_E "Kalibracja E skonczona. Prosze oczyscic dysze. Potem potwierdzic przyciskiem. "
|
||||
#define MSG_WAITING_TEMP "Oczekiwanie na wychlodzenie dyszy i podkladki."
|
||||
#define MSG_FILAMENT_CLEAN "Czy kolor jest czysty?"
|
||||
#define MSG_UNLOADING_FILAMENT "Wysuwam filament"
|
||||
#define MSG_PAPER "Umiesc kartke papieru na podkladce i trzymaj pod dysza podczas pomiaru pierwszych 4 punktow. Jesli dysza zahaczy o papier, wylacz drukarke."
|
||||
|
||||
#define MSG_FINISHING_MOVEMENTS "Konczenie druku"
|
||||
#define MSG_PRINT_PAUSED "Druk zatrzymany"
|
||||
#define MSG_RESUMING_PRINT "Wznawianie druku"
|
||||
#define MSG_PID_EXTRUDER "Kalibracja PID"
|
||||
#define MSG_SET_TEMPERATURE "Ustawic temperature"
|
||||
#define MSG_PID_FINISHED "Kal. PID zakonczona"
|
||||
#define MSG_PID_RUNNING "Kal. PID"
|
||||
|
||||
#define MSG_CALIBRATE_PINDA "Skalibrowac"
|
||||
#define MSG_CALIBRATION_PINDA_MENU "Cieplna kalibr."
|
||||
#define MSG_PINDA_NOT_CALIBRATED "Cieplna kalibracja nie byla przeprowadzona"
|
||||
#define MSG_PINDA_PREHEAT "Grzanie PINDA"
|
||||
#define MSG_TEMP_CALIBRATION "Ciepl. kal. "
|
||||
#define MSG_TEMP_CALIBRATION_DONE "Cieplna kalibracja zakonczona. Kontynuuj przyciskiem"
|
||||
#define MSG_TEMP_CALIBRATION_ON "Ciepl. kal. [ON]"
|
||||
#define MSG_TEMP_CALIBRATION_OFF "Ciepl. kal. [OFF]"
|
||||
#define MSG_PREPARE_FILAMENT "Przygotuj filament"
|
||||
|
||||
#define MSG_LOAD_ALL "Zalad. wszystkie"
|
||||
#define MSG_LOAD_FILAMENT_1 "Zaladowac fil. 1"
|
||||
#define MSG_LOAD_FILAMENT_2 "Zaladowac fil. 2"
|
||||
#define MSG_LOAD_FILAMENT_3 "Zaladowac fil. 3"
|
||||
#define MSG_LOAD_FILAMENT_4 "Zaladowac fil. 4"
|
||||
#define MSG_UNLOAD_FILAMENT_1 "Wyjac filament 1"
|
||||
#define MSG_UNLOAD_FILAMENT_2 "Wyjac filament 2"
|
||||
#define MSG_UNLOAD_FILAMENT_3 "Wyjac filament 3"
|
||||
#define MSG_UNLOAD_FILAMENT_4 "Wyjac filament 4"
|
||||
#define MSG_UNLOAD_ALL "Wyjac wszystkie"
|
||||
#define MSG_PREPARE_FILAMENT "Przygotuj filament"
|
||||
#define MSG_ALL "Wszystko"
|
||||
#define MSG_USED "Uzyte przy druku"
|
||||
#define MSG_CURRENT "Tylko aktualne"
|
||||
#define MSG_CHOOSE_EXTRUDER "Wybierz ekstruder"
|
||||
#define MSG_EXTRUDER "Ekstruder"
|
||||
#define MSG_EXTRUDER_1 "Ekstruder 1"
|
||||
#define MSG_EXTRUDER_2 "Ekstruder 2"
|
||||
#define MSG_EXTRUDER_3 "Ekstruder 3"
|
||||
#define MSG_EXTRUDER_4 "Ekstruder 4"
|
||||
|
||||
#define MSG_WIZARD "Wizard"
|
||||
#define MSG_WIZARD_WELCOME "Czesc, jestem Twoja drukarka Original Prusa i3. Czy potrzebujesz pomocy z instalacja?"
|
||||
#define MSG_WIZARD_QUIT "Zawsze mozesz przywrocic Wizard przez Kalibracja -> Wizard."
|
||||
#define MSG_WIZARD_SELFTEST "Najpierw wlacze autotest w celu kontrolli najczestszych problemow z montazem."
|
||||
#define MSG_WIZARD_CALIBRATION_FAILED "Prosze sprawdz nasz poradnik i napraw problem. Potem przywroc Wizard restartujac drukarke."
|
||||
#define MSG_WIZARD_XYZ_CAL "Wlaczam kalibracje xyz. Zajmie to ok. 12 min."
|
||||
#define MSG_WIZARD_FILAMENT_LOADED "Filament jest zaladowany?"
|
||||
#define MSG_WIZARD_Z_CAL "Wlaczam kalibracje z."
|
||||
#define MSG_WIZARD_WILL_PREHEAT "Nagrzewam dysze dla PLA."
|
||||
#define MSG_WIZARD_V2_CAL "Kalibruje odleglosc miedzy koncowka dyszy a stolikiem."
|
||||
#define MSG_WIZARD_V2_CAL_2 "Zaczne drukowac linie. Stopniowo opuszczaj dysze przekrecajac guzik, poki nie uzyskasz optymalnej wysokosci. Sprawdz obrazki w naszym poradniku w rozdz. Kalibracja"
|
||||
#define MSG_V2_CALIBRATION "Kal. 1. warstwy"
|
||||
#define MSG_WIZARD_DONE "Gotowe. Udanego druku!"
|
||||
#define MSG_WIZARD_LOAD_FILAMENT "Prosze umiesc filament PLA w ekstruderze i nacisnij przycisk by zaladowac."
|
||||
#define MSG_WIZARD_RERUN "Wlaczenie Wizard usunie obecne dane kalibracyjne i zacznie od nowa. Kontynuowac?"
|
||||
#define MSG_WIZARD_REPEAT_V2_CAL "Chcesz powtorzyc ostatni krok i przestawic odleglosc miedzy dysza a stolikiem?"
|
||||
#define MSG_WIZARD_CLEAN_HEATBED "Prosze oczysc stolik i nacisnij guzik."
|
||||
#define MSG_WIZARD_PLA_FILAMENT "Czy to filament PLA?"
|
||||
#define MSG_WIZARD_INSERT_CORRECT_FILAMENT "Prosze zaladuj filament PLA i przywroc Wizard przez restart drukarki."
|
||||
#define MSG_PLA_FILAMENT_LOADED "Fialment PLA jest zaladowany?"
|
||||
#define MSG_PLEASE_LOAD_PLA "Prosze, najpierw zaladuj filament PLA."
|
||||
#define MSG_WIZARD_HEATING "Nagrzewanie dyszy. Prosze czekac."
|
||||
#define MSG_M117_V2_CALIBRATION "M117 Kal. 1. warstwy"
|
||||
|
||||
#define MSG_DATE "Data:"
|
||||
#define MSG_XYZ_DETAILS "Szczegoly kal.XYZ"
|
||||
#define MSG_Y_DISTANCE_FROM_MIN "Odleglosc Y od min.:"
|
||||
#define MSG_LEFT "Lewy:"
|
||||
#define MSG_RIGHT "Prawy:"
|
||||
#define MSG_MEASURED_SKEW "Zmier. sciecie:"
|
||||
#define MSG_SLIGHT_SKEW "Lekkie sciecie:"
|
||||
#define MSG_SEVERE_SKEW "Ostre sciecie:"
|
29
Firmware/le.sh
Normal file
29
Firmware/le.sh
Normal file
|
@ -0,0 +1,29 @@
|
|||
# line ending management script
|
||||
# CRLF - windows default ('\r\n')
|
||||
# LF - unix default ('\n')
|
||||
# arguments:
|
||||
# ?crlf - print all .cpp and .h files with CRLF line endings
|
||||
# ?lf - print all .cpp and .h files with LF line endings
|
||||
# crlf - replace line endings in all .cpp and .h files to CRLF
|
||||
# lf - replace line endings in all .cpp and .h files to LF
|
||||
|
||||
if [ "$1" == "?crlf" ] || [ $# -eq 0 ]; then
|
||||
echo 'cpp and h files with CRLF line endings:'
|
||||
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep CRLF | sed 's/:.*//g'
|
||||
elif [ "$1" == "?lf" ]; then
|
||||
echo 'cpp and h files with LF line endings:'
|
||||
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep -v CRLF | sed 's/:.*//g'
|
||||
fi
|
||||
if [ "$1" == "crlf" ]; then
|
||||
echo 'replacing LF with CRLF in all cpp and h files:'
|
||||
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep -v CRLF | sed 's/:.*//g' | while read fn; do
|
||||
echo "$fn"
|
||||
sed -i 's/$/\r/g' $fn
|
||||
done
|
||||
elif [ "$1" == "lf" ]; then
|
||||
echo 'replacing CRLF with LF in all cpp and h files:'
|
||||
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep CRLF | sed 's/:.*//g' | while read fn; do
|
||||
echo "$fn"
|
||||
sed -i 's/\r\n/\n/g' $fn
|
||||
done
|
||||
fi
|
File diff suppressed because it is too large
Load diff
|
@ -1,170 +1,191 @@
|
|||
#ifndef MESH_BED_CALIBRATION_H
|
||||
#define MESH_BED_CALIBRATION_H
|
||||
|
||||
// Exact positions of the print head above the bed reference points, in the world coordinates.
|
||||
// The world coordinates match the machine coordinates only in case, when the machine
|
||||
// is built properly, the end stops are at the correct positions and the axes are perpendicular.
|
||||
extern const float bed_ref_points[] PROGMEM;
|
||||
|
||||
// Is the world2machine correction activated?
|
||||
enum World2MachineCorrectionMode
|
||||
{
|
||||
WORLD2MACHINE_CORRECTION_NONE = 0,
|
||||
WORLD2MACHINE_CORRECTION_SHIFT = 1,
|
||||
WORLD2MACHINE_CORRECTION_SKEW = 2,
|
||||
};
|
||||
extern uint8_t world2machine_correction_mode;
|
||||
// 2x2 transformation matrix from the world coordinates to the machine coordinates.
|
||||
// Corrects for the rotation and skew of the machine axes.
|
||||
// Used by the planner's plan_buffer_line() and plan_set_position().
|
||||
extern float world2machine_rotation_and_skew[2][2];
|
||||
extern float world2machine_rotation_and_skew_inv[2][2];
|
||||
// Shift of the machine zero point, in the machine coordinates.
|
||||
extern float world2machine_shift[2];
|
||||
|
||||
// Resets the transformation to identity.
|
||||
extern void world2machine_reset();
|
||||
// Resets the transformation to identity and update current_position[X,Y] from the servos.
|
||||
extern void world2machine_revert_to_uncorrected();
|
||||
// Loads the transformation from the EEPROM, if available.
|
||||
extern void world2machine_initialize();
|
||||
|
||||
// When switching from absolute to corrected coordinates,
|
||||
// this will apply an inverse world2machine transformation
|
||||
// to current_position[x,y].
|
||||
extern void world2machine_update_current();
|
||||
|
||||
inline void world2machine(const float &x, const float &y, float &out_x, float &out_y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
out_x = x;
|
||||
out_y = y;
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
out_x = world2machine_rotation_and_skew[0][0] * x + world2machine_rotation_and_skew[0][1] * y;
|
||||
out_y = world2machine_rotation_and_skew[1][0] * x + world2machine_rotation_and_skew[1][1] * y;
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
out_x += world2machine_shift[0];
|
||||
out_y += world2machine_shift[1];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void world2machine(float &x, float &y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
float out_x = world2machine_rotation_and_skew[0][0] * x + world2machine_rotation_and_skew[0][1] * y;
|
||||
float out_y = world2machine_rotation_and_skew[1][0] * x + world2machine_rotation_and_skew[1][1] * y;
|
||||
x = out_x;
|
||||
y = out_y;
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
x += world2machine_shift[0];
|
||||
y += world2machine_shift[1];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void machine2world(float x, float y, float &out_x, float &out_y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
out_x = x;
|
||||
out_y = y;
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
x -= world2machine_shift[0];
|
||||
y -= world2machine_shift[1];
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
out_x = world2machine_rotation_and_skew_inv[0][0] * x + world2machine_rotation_and_skew_inv[0][1] * y;
|
||||
out_y = world2machine_rotation_and_skew_inv[1][0] * x + world2machine_rotation_and_skew_inv[1][1] * y;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void machine2world(float &x, float &y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
x -= world2machine_shift[0];
|
||||
y -= world2machine_shift[1];
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
float out_x = world2machine_rotation_and_skew_inv[0][0] * x + world2machine_rotation_and_skew_inv[0][1] * y;
|
||||
float out_y = world2machine_rotation_and_skew_inv[1][0] * x + world2machine_rotation_and_skew_inv[1][1] * y;
|
||||
x = out_x;
|
||||
y = out_y;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline bool world2machine_clamp(float &x, float &y)
|
||||
{
|
||||
bool clamped = false;
|
||||
float tmpx, tmpy;
|
||||
world2machine(x, y, tmpx, tmpy);
|
||||
if (tmpx < X_MIN_POS) {
|
||||
tmpx = X_MIN_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (tmpy < Y_MIN_POS) {
|
||||
tmpy = Y_MIN_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (tmpx > X_MAX_POS) {
|
||||
tmpx = X_MAX_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (tmpy > Y_MAX_POS) {
|
||||
tmpy = Y_MAX_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (clamped)
|
||||
machine2world(tmpx, tmpy, x, y);
|
||||
return clamped;
|
||||
}
|
||||
|
||||
extern bool find_bed_induction_sensor_point_z(float minimum_z = -10.f, uint8_t n_iter = 3);
|
||||
extern bool find_bed_induction_sensor_point_xy();
|
||||
|
||||
// Positive or zero: ok
|
||||
// Negative: failed
|
||||
enum BedSkewOffsetDetectionResultType {
|
||||
// Detection failed, some point was not found.
|
||||
BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND = -1,
|
||||
BED_SKEW_OFFSET_DETECTION_FITTING_FAILED = -2,
|
||||
|
||||
// Detection finished with success.
|
||||
BED_SKEW_OFFSET_DETECTION_PERFECT = 0,
|
||||
BED_SKEW_OFFSET_DETECTION_SKEW_MILD = 1,
|
||||
BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME = 2
|
||||
};
|
||||
|
||||
extern BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level);
|
||||
extern BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8_t verbosity_level, uint8_t &too_far_mask);
|
||||
|
||||
extern void reset_bed_offset_and_skew();
|
||||
extern bool is_bed_z_jitter_data_valid();
|
||||
|
||||
// Scan the mesh bed induction points one by one by a left-right zig-zag movement,
|
||||
// write the trigger coordinates to the serial line.
|
||||
// Useful for visualizing the behavior of the bed induction detector.
|
||||
extern bool scan_bed_induction_points(int8_t verbosity_level);
|
||||
|
||||
#endif /* MESH_BED_CALIBRATION_H */
|
||||
#ifndef MESH_BED_CALIBRATION_H
|
||||
#define MESH_BED_CALIBRATION_H
|
||||
|
||||
// Exact positions of the print head above the bed reference points, in the world coordinates.
|
||||
// The world coordinates match the machine coordinates only in case, when the machine
|
||||
// is built properly, the end stops are at the correct positions and the axes are perpendicular.
|
||||
extern const float bed_ref_points[] PROGMEM;
|
||||
|
||||
extern const float bed_skew_angle_mild;
|
||||
extern const float bed_skew_angle_extreme;
|
||||
|
||||
// Is the world2machine correction activated?
|
||||
enum World2MachineCorrectionMode
|
||||
{
|
||||
WORLD2MACHINE_CORRECTION_NONE = 0,
|
||||
WORLD2MACHINE_CORRECTION_SHIFT = 1,
|
||||
WORLD2MACHINE_CORRECTION_SKEW = 2,
|
||||
};
|
||||
extern uint8_t world2machine_correction_mode;
|
||||
// 2x2 transformation matrix from the world coordinates to the machine coordinates.
|
||||
// Corrects for the rotation and skew of the machine axes.
|
||||
// Used by the planner's plan_buffer_line() and plan_set_position().
|
||||
extern float world2machine_rotation_and_skew[2][2];
|
||||
extern float world2machine_rotation_and_skew_inv[2][2];
|
||||
// Shift of the machine zero point, in the machine coordinates.
|
||||
extern float world2machine_shift[2];
|
||||
|
||||
// Resets the transformation to identity.
|
||||
extern void world2machine_reset();
|
||||
// Resets the transformation to identity and update current_position[X,Y] from the servos.
|
||||
extern void world2machine_revert_to_uncorrected();
|
||||
// Loads the transformation from the EEPROM, if available.
|
||||
extern void world2machine_initialize();
|
||||
|
||||
// When switching from absolute to corrected coordinates,
|
||||
// this will apply an inverse world2machine transformation
|
||||
// to current_position[x,y].
|
||||
extern void world2machine_update_current();
|
||||
|
||||
inline void world2machine(const float &x, const float &y, float &out_x, float &out_y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
out_x = x;
|
||||
out_y = y;
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
out_x = world2machine_rotation_and_skew[0][0] * x + world2machine_rotation_and_skew[0][1] * y;
|
||||
out_y = world2machine_rotation_and_skew[1][0] * x + world2machine_rotation_and_skew[1][1] * y;
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
out_x += world2machine_shift[0];
|
||||
out_y += world2machine_shift[1];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void world2machine(float &x, float &y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
float out_x = world2machine_rotation_and_skew[0][0] * x + world2machine_rotation_and_skew[0][1] * y;
|
||||
float out_y = world2machine_rotation_and_skew[1][0] * x + world2machine_rotation_and_skew[1][1] * y;
|
||||
x = out_x;
|
||||
y = out_y;
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
x += world2machine_shift[0];
|
||||
y += world2machine_shift[1];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void machine2world(float x, float y, float &out_x, float &out_y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
out_x = x;
|
||||
out_y = y;
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
x -= world2machine_shift[0];
|
||||
y -= world2machine_shift[1];
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
out_x = world2machine_rotation_and_skew_inv[0][0] * x + world2machine_rotation_and_skew_inv[0][1] * y;
|
||||
out_y = world2machine_rotation_and_skew_inv[1][0] * x + world2machine_rotation_and_skew_inv[1][1] * y;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void machine2world(float &x, float &y)
|
||||
{
|
||||
if (world2machine_correction_mode == WORLD2MACHINE_CORRECTION_NONE) {
|
||||
// No correction.
|
||||
} else {
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SHIFT) {
|
||||
// Then add the offset.
|
||||
x -= world2machine_shift[0];
|
||||
y -= world2machine_shift[1];
|
||||
}
|
||||
if (world2machine_correction_mode & WORLD2MACHINE_CORRECTION_SKEW) {
|
||||
// Firs the skew & rotation correction.
|
||||
float out_x = world2machine_rotation_and_skew_inv[0][0] * x + world2machine_rotation_and_skew_inv[0][1] * y;
|
||||
float out_y = world2machine_rotation_and_skew_inv[1][0] * x + world2machine_rotation_and_skew_inv[1][1] * y;
|
||||
x = out_x;
|
||||
y = out_y;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline bool world2machine_clamp(float &x, float &y)
|
||||
{
|
||||
bool clamped = false;
|
||||
float tmpx, tmpy;
|
||||
world2machine(x, y, tmpx, tmpy);
|
||||
if (tmpx < X_MIN_POS) {
|
||||
tmpx = X_MIN_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (tmpy < Y_MIN_POS) {
|
||||
tmpy = Y_MIN_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (tmpx > X_MAX_POS) {
|
||||
tmpx = X_MAX_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (tmpy > Y_MAX_POS) {
|
||||
tmpy = Y_MAX_POS;
|
||||
clamped = true;
|
||||
}
|
||||
if (clamped)
|
||||
machine2world(tmpx, tmpy, x, y);
|
||||
return clamped;
|
||||
}
|
||||
|
||||
extern bool find_bed_induction_sensor_point_z(float minimum_z = -10.f, uint8_t n_iter = 3, int verbosity_level = 0);
|
||||
extern bool find_bed_induction_sensor_point_xy(int verbosity_level = 0);
|
||||
extern void go_home_with_z_lift();
|
||||
|
||||
// Positive or zero: ok
|
||||
// Negative: failed
|
||||
enum BedSkewOffsetDetectionResultType {
|
||||
// Detection failed, some point was not found.
|
||||
BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND = -1,
|
||||
BED_SKEW_OFFSET_DETECTION_FITTING_FAILED = -2,
|
||||
|
||||
// Detection finished with success.
|
||||
BED_SKEW_OFFSET_DETECTION_PERFECT = 0,
|
||||
BED_SKEW_OFFSET_DETECTION_SKEW_MILD = 1,
|
||||
BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME = 2
|
||||
};
|
||||
|
||||
extern BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level, uint8_t &too_far_mask);
|
||||
extern BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8_t verbosity_level, uint8_t &too_far_mask);
|
||||
|
||||
extern bool sample_mesh_and_store_reference();
|
||||
|
||||
extern void reset_bed_offset_and_skew();
|
||||
extern bool is_bed_z_jitter_data_valid();
|
||||
|
||||
// Scan the mesh bed induction points one by one by a left-right zig-zag movement,
|
||||
// write the trigger coordinates to the serial line.
|
||||
// Useful for visualizing the behavior of the bed induction detector.
|
||||
extern bool scan_bed_induction_points(int8_t verbosity_level);
|
||||
|
||||
// Load Z babystep value from the EEPROM into babystepLoadZ,
|
||||
// but don't apply it through the planner. This is useful on wake up
|
||||
// after power panic, when it is expected, that the baby step has been already applied.
|
||||
extern void babystep_load();
|
||||
|
||||
// Apply Z babystep value from the EEPROM through the planner.
|
||||
extern void babystep_apply();
|
||||
|
||||
// Undo the current Z babystep value.
|
||||
extern void babystep_undo();
|
||||
|
||||
// Reset the current babystep counter without moving the axes.
|
||||
extern void babystep_reset();
|
||||
extern void count_xyz_details();
|
||||
|
||||
#endif /* MESH_BED_CALIBRATION_H */
|
||||
|
|
139
Firmware/pat9125.cpp
Executable file
139
Firmware/pat9125.cpp
Executable file
|
@ -0,0 +1,139 @@
|
|||
#include "uni_avr_rpi.h"
|
||||
|
||||
#ifdef PAT9125
|
||||
|
||||
#include "pat9125.h"
|
||||
|
||||
#ifdef PAT9125_SWSPI
|
||||
#include "swspi.h"
|
||||
#endif //PAT9125_SWSPI
|
||||
#ifdef PAT9125_SWI2C
|
||||
#include "swi2c.h"
|
||||
#endif //PAT9125_SWI2C
|
||||
#ifdef PAT9125_HWI2C
|
||||
#include <Wire.h>
|
||||
#endif //PAT9125_HWI2C
|
||||
|
||||
|
||||
unsigned char pat9125_PID1 = 0;
|
||||
unsigned char pat9125_PID2 = 0;
|
||||
unsigned char pat9125_xres = 0;
|
||||
unsigned char pat9125_yres = 0;
|
||||
int pat9125_x = 0;
|
||||
int pat9125_y = 0;
|
||||
unsigned char pat9125_b = 0;
|
||||
unsigned char pat9125_s = 0;
|
||||
|
||||
int pat9125_init(unsigned char xres, unsigned char yres)
|
||||
{
|
||||
#ifdef PAT9125_SWSPI
|
||||
swspi_init();
|
||||
#endif //PAT9125_SWSPI
|
||||
#ifdef PAT9125_SWI2C
|
||||
swi2c_init(PAT9125_SWI2C_SDA, PAT9125_SWI2C_SCL, PAT9125_SWI2C_CFG);
|
||||
#endif //PAT9125_SWI2C
|
||||
#ifdef PAT9125_HWI2C
|
||||
Wire.begin();
|
||||
#endif //PAT9125_HWI2C
|
||||
pat9125_xres = xres;
|
||||
pat9125_yres = yres;
|
||||
pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
|
||||
pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2);
|
||||
// pat9125_PID1 = 0x31;
|
||||
// pat9125_PID2 = 0x91;
|
||||
if ((pat9125_PID1 != 0x31) || (pat9125_PID2 != 0x91))
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
pat9125_wr_reg(PAT9125_RES_X, pat9125_xres);
|
||||
pat9125_wr_reg(PAT9125_RES_Y, pat9125_yres);
|
||||
// pat9125_wr_reg(PAT9125_ORIENTATION, 0x04 | (xinv?0x08:0) | (yinv?0x10:0)); //!? direction switching does not work
|
||||
return 1;
|
||||
}
|
||||
|
||||
int pat9125_update()
|
||||
{
|
||||
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
|
||||
{
|
||||
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
|
||||
pat9125_b = pat9125_rd_reg(PAT9125_FRAME);
|
||||
pat9125_s = pat9125_rd_reg(PAT9125_SHUTTER);
|
||||
if (ucMotion & 0x80)
|
||||
{
|
||||
unsigned char ucXL = pat9125_rd_reg(PAT9125_DELTA_XL);
|
||||
unsigned char ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
|
||||
unsigned char ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
|
||||
int iDX = ucXL | ((ucXYH << 4) & 0xf00);
|
||||
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
|
||||
if (iDX & 0x800) iDX -= 4096;
|
||||
if (iDY & 0x800) iDY -= 4096;
|
||||
pat9125_x += iDX;
|
||||
pat9125_y -= iDY; //negative number, because direction switching does not work
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int pat9125_update_y()
|
||||
{
|
||||
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
|
||||
{
|
||||
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
|
||||
if (ucMotion & 0x80)
|
||||
{
|
||||
unsigned char ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
|
||||
unsigned char ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
|
||||
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
|
||||
if (iDY & 0x800) iDY -= 4096;
|
||||
pat9125_y -= iDY; //negative number, because direction switching does not work
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned char pat9125_rd_reg(unsigned char addr)
|
||||
{
|
||||
unsigned char data = 0;
|
||||
#ifdef PAT9125_SWSPI
|
||||
swspi_start();
|
||||
swspi_tx(addr & 0x7f);
|
||||
data = swspi_rx();
|
||||
swspi_stop();
|
||||
#endif //PAT9125_SWSPI
|
||||
#ifdef PAT9125_SWI2C
|
||||
int iret = swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data);
|
||||
#endif //PAT9125_SWI2C
|
||||
#ifdef PAT9125_HWI2C
|
||||
Wire.beginTransmission(PAT9125_I2C_ADDR);
|
||||
Wire.write(addr);
|
||||
Wire.endTransmission();
|
||||
if (Wire.requestFrom(PAT9125_I2C_ADDR, 1) == 1)
|
||||
// if (Wire.available())
|
||||
data = Wire.read();
|
||||
#endif //PAT9125_HWI2C
|
||||
return data;
|
||||
}
|
||||
|
||||
void pat9125_wr_reg(unsigned char addr, unsigned char data)
|
||||
{
|
||||
#ifdef PAT9125_SWSPI
|
||||
swspi_start();
|
||||
swspi_tx(addr | 0x80);
|
||||
swspi_tx(data);
|
||||
swspi_stop();
|
||||
#endif //PAT9125_SWSPI
|
||||
#ifdef PAT9125_SWI2C
|
||||
int iret = swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data);
|
||||
#endif //PAT9125_SWI2C
|
||||
#ifdef PAT9125_HWI2C
|
||||
Wire.beginTransmission(PAT9125_I2C_ADDR);
|
||||
Wire.write(addr);
|
||||
Wire.write(data);
|
||||
Wire.endTransmission();
|
||||
#endif //PAT9125_HWI2C
|
||||
|
||||
}
|
||||
|
||||
#endif //PAT9125
|
46
Firmware/pat9125.h
Executable file
46
Firmware/pat9125.h
Executable file
|
@ -0,0 +1,46 @@
|
|||
#ifndef PAT9125_H
|
||||
#define PAT9125_H
|
||||
|
||||
//PAT9125 I2C
|
||||
#define PAT9125_I2C_ADDR 0x75 //ID=LO
|
||||
//#define PAT9125_I2C_ADDR 0x79 //ID=HI
|
||||
//#define PAT9125_I2C_ADDR 0x73 //ID=NC
|
||||
|
||||
//PAT9125 registers
|
||||
#define PAT9125_PID1 0x00
|
||||
#define PAT9125_PID2 0x01
|
||||
#define PAT9125_MOTION 0x02
|
||||
#define PAT9125_DELTA_XL 0x03
|
||||
#define PAT9125_DELTA_YL 0x04
|
||||
#define PAT9125_MODE 0x05
|
||||
#define PAT9125_CONFIG 0x06
|
||||
#define PAT9125_WP 0x09
|
||||
#define PAT9125_SLEEP1 0x0a
|
||||
#define PAT9125_SLEEP2 0x0b
|
||||
#define PAT9125_RES_X 0x0d
|
||||
#define PAT9125_RES_Y 0x0e
|
||||
#define PAT9125_DELTA_XYH 0x12
|
||||
#define PAT9125_SHUTTER 0x14
|
||||
#define PAT9125_FRAME 0x17
|
||||
#define PAT9125_ORIENTATION 0x19
|
||||
|
||||
extern unsigned char pat9125_PID1;
|
||||
extern unsigned char pat9125_PID2;
|
||||
|
||||
extern unsigned char pat9125_xres;
|
||||
extern unsigned char pat9125_yres;
|
||||
|
||||
extern int pat9125_x;
|
||||
extern int pat9125_y;
|
||||
extern unsigned char pat9125_b;
|
||||
extern unsigned char pat9125_s;
|
||||
|
||||
extern int pat9125_init(unsigned char xres, unsigned char yres);
|
||||
extern int pat9125_update();
|
||||
extern int pat9125_update_y();
|
||||
|
||||
extern unsigned char pat9125_rd_reg(unsigned char addr);
|
||||
extern void pat9125_wr_reg(unsigned char addr, unsigned char data);
|
||||
|
||||
|
||||
#endif //PAT9125_H
|
284
Firmware/pins.h
284
Firmware/pins.h
|
@ -22,278 +22,30 @@
|
|||
/*****************************************************************
|
||||
* Rambo Pin Assignments 1.3
|
||||
******************************************************************/
|
||||
#if MOTHERBOARD == 302
|
||||
#define MINI_RAMBO
|
||||
|
||||
#endif
|
||||
#if MOTHERBOARD == 301 || MOTHERBOARD == 302
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
|
||||
#define FR_SENS 21
|
||||
#if MOTHERBOARD == 100 //100 - orig 301
|
||||
#include "pins_Rambo.h"
|
||||
#endif //MOTHERBOARD == 100
|
||||
|
||||
#if MOTHERBOARD == 200 //200 - orig 102
|
||||
#include "pins_Rambo_1_0.h"
|
||||
#endif //MOTHERBOARD == 200
|
||||
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 48
|
||||
#define X_MIN_PIN 12
|
||||
#define X_MAX_PIN 24
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN 40
|
||||
#define X_MS2_PIN 41
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 49
|
||||
#define Y_MIN_PIN 11
|
||||
#define Y_MAX_PIN 23
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN 69
|
||||
#define Y_MS2_PIN 39
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 30
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN 68
|
||||
#define Z_MS2_PIN 67
|
||||
#define TEMP_BED_PIN 2
|
||||
#define TEMP_0_PIN 0
|
||||
#define HEATER_1_PIN 7
|
||||
#define TEMP_1_PIN 1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||
#define SDSS 53
|
||||
|
||||
#ifndef SDSUPPORT
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#endif
|
||||
|
||||
#define BEEPER 84
|
||||
|
||||
#define BTN_EN1 72
|
||||
#define BTN_EN2 14
|
||||
#define BTN_ENC 9
|
||||
|
||||
#define SDCARDDETECT 15
|
||||
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
|
||||
|
||||
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN 65
|
||||
#define E0_MS2_PIN 66
|
||||
#define LED_PIN 13
|
||||
#ifdef THREEMM_PRINTER
|
||||
#define FAN_PIN 8
|
||||
#else
|
||||
#define FAN_PIN 6
|
||||
#endif
|
||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||
#define SDPOWER -1
|
||||
#define HEATER_2_PIN -1
|
||||
#ifdef MINI_RAMBO
|
||||
|
||||
#define ELECTRONICS "RAMBo13a"
|
||||
|
||||
#define HEATER_0_PIN 3
|
||||
#define HEATER_BED_PIN 4
|
||||
#define FAN_1_PIN -1 //6
|
||||
#define PS_ON_PIN 71
|
||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
||||
|
||||
#else //RAMBo
|
||||
#define ELECTRONICS "RAMBoBig"
|
||||
|
||||
#define E1_STEP_PIN 33
|
||||
#define E1_DIR_PIN 42
|
||||
#define E1_ENABLE_PIN 25
|
||||
#define E1_MS1_PIN 63
|
||||
#define E1_MS2_PIN 64
|
||||
#define DIGIPOTSS_PIN 38
|
||||
#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping
|
||||
#define HEATER_0_PIN 9
|
||||
#define HEATER_BED_PIN 3
|
||||
#define PS_ON_PIN 4
|
||||
#define SDSS 53
|
||||
#ifdef ULTRA_LCD
|
||||
#define KILL_PIN 80
|
||||
#ifdef NEWPANEL
|
||||
//arduino pin which triggers an piezzo beeper
|
||||
#define BEEPER 84 // Beeper on AUX-4
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
//buttons are directly attached using AUX-2
|
||||
#define BTN_EN1 76
|
||||
#define BTN_EN2 77
|
||||
#define BTN_ENC 78 //the click
|
||||
#define BLEN_C 2
|
||||
#define BLEN_B 1
|
||||
#define BLEN_A 0
|
||||
#define SDCARDDETECT 81 // Ramps does not use this port
|
||||
//encoder rotation values
|
||||
#define encrot0 0
|
||||
#define encrot1 2
|
||||
#define encrot2 3
|
||||
#define encrot3 1
|
||||
#else //old style panel with shift register
|
||||
//arduino pin witch triggers an piezzo beeper
|
||||
#define BEEPER 84 //No Beeper added
|
||||
//buttons are attached to a shift register
|
||||
// Not wired this yet
|
||||
// #define SHIFT_CLK 38
|
||||
// #define SHIFT_LD 42
|
||||
// #define SHIFT_OUT 40
|
||||
// #define SHIFT_EN 17
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
//encoder rotation values
|
||||
#define encrot0 0
|
||||
#define encrot1 2
|
||||
#define encrot2 3
|
||||
#define encrot3 1
|
||||
//bits in the shift register that carry the buttons for:
|
||||
// left up center down right red
|
||||
#define BL_LE 7
|
||||
#define BL_UP 6
|
||||
#define BL_MI 5
|
||||
#define BL_DW 4
|
||||
#define BL_RI 3
|
||||
#define BL_ST 2
|
||||
#define BLEN_B 1
|
||||
#define BLEN_A 0
|
||||
#endif
|
||||
#endif //ULTRA_LCD
|
||||
#endif //RAMBo/MiniRambo option
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/*****************************************************************
|
||||
* Rambo mini Pin Assignments 1.0
|
||||
******************************************************************/
|
||||
#if MOTHERBOARD == 102
|
||||
#define ELECTRONICS "RAMBo10a"
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
#define FR_SENS 21
|
||||
|
||||
#define LARGE_FLASH true
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 48
|
||||
#define X_MIN_PIN 12
|
||||
#define X_MAX_PIN 24
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN 40
|
||||
#define X_MS2_PIN 41
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 49
|
||||
#define Y_MIN_PIN 11
|
||||
#define Y_MAX_PIN 23
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN 69
|
||||
#define Y_MS2_PIN 39
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 30
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN 68
|
||||
#define Z_MS2_PIN 67
|
||||
#define TEMP_BED_PIN 2
|
||||
#define TEMP_0_PIN 0
|
||||
#define HEATER_1_PIN 7
|
||||
#define TEMP_1_PIN 1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||
#define SDSS 53
|
||||
|
||||
#ifndef SDSUPPORT
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#endif
|
||||
|
||||
#define BEEPER 78
|
||||
|
||||
#define BTN_EN1 80
|
||||
#define BTN_EN2 73
|
||||
#define BTN_ENC 21
|
||||
|
||||
#define SDCARDDETECT 72
|
||||
|
||||
#define LCD_PINS_RS 38
|
||||
#define LCD_PINS_ENABLE 5
|
||||
#define LCD_PINS_D4 14
|
||||
#define LCD_PINS_D5 15
|
||||
#define LCD_PINS_D6 32
|
||||
#define LCD_PINS_D7 31
|
||||
|
||||
|
||||
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN 65
|
||||
#define E0_MS2_PIN 66
|
||||
#define LED_PIN 13
|
||||
#ifdef THREEMM_PRINTER
|
||||
#define FAN_PIN 8
|
||||
#else
|
||||
#define FAN_PIN 6
|
||||
#endif
|
||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||
#define SDPOWER -1
|
||||
#define HEATER_2_PIN -1
|
||||
|
||||
#define HEATER_0_PIN 3
|
||||
#define HEATER_BED_PIN 4
|
||||
#define FAN_1_PIN -1 //6
|
||||
#define PS_ON_PIN 71
|
||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
#if MOTHERBOARD == 203 //203 - orig 302
|
||||
#include "pins_Rambo_1_3.h"
|
||||
#endif //MOTHERBOARD == 203
|
||||
|
||||
#if MOTHERBOARD == 303 //303 - orig 300
|
||||
#include "pins_Einy_0_3.h"
|
||||
#endif //MOTHERBOARD == 303
|
||||
|
||||
#if MOTHERBOARD == 304 //304 - orig 299
|
||||
#include "pins_Einy_0_4.h"
|
||||
#endif //MOTHERBOARD == 304
|
||||
|
||||
#if MOTHERBOARD == 305 //305 - orig 298
|
||||
#include "pins_Einy_0_4.h"
|
||||
#endif //MOTHERBOARD == 305
|
||||
|
||||
#ifndef KNOWN_BOARD
|
||||
#error Unknown MOTHERBOARD value in configuration.h
|
||||
|
|
129
Firmware/pins_Einy_0_3.h
Normal file
129
Firmware/pins_Einy_0_3.h
Normal file
|
@ -0,0 +1,129 @@
|
|||
/*****************************************************************
|
||||
* EINY Rambo 0.3a Pin Assignments
|
||||
******************************************************************/
|
||||
|
||||
#define ELECTRONICS "EINY_03a"
|
||||
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
#define TMC2130
|
||||
#define PAT9125
|
||||
|
||||
#define SWI2C // enable software i2c
|
||||
#define SWI2C_A8 // 8bit address functions
|
||||
|
||||
#define PAT9125_SWI2C
|
||||
#define PAT9125_SWI2C_SDA 20 //SDA on P3
|
||||
#define PAT9125_SWI2C_SCL 21 //SCL on P3
|
||||
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
|
||||
|
||||
//#define SWSPI_MISO 16 //RX2
|
||||
//#define SWSPI_MOSI 16 //RX2
|
||||
//#define SWSPI_SCK 17 //TX2
|
||||
//#define SWSPI_CS 20 //SDA
|
||||
|
||||
////#define SWI2C_SDA 20 //SDA
|
||||
////#define SWI2C_SCL 21 //SCL
|
||||
//#define SWI2C_SDA 16 //RX2
|
||||
//#define SWI2C_SCL 17 //TX2
|
||||
|
||||
#define X_TMC2130_CS 41
|
||||
#define X_TMC2130_DIAG 40
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 49
|
||||
//#define X_MIN_PIN 12
|
||||
//#define X_MAX_PIN 30
|
||||
#define X_MIN_PIN X_TMC2130_DIAG
|
||||
#define X_MAX_PIN X_TMC2130_DIAG
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN -1
|
||||
#define X_MS2_PIN -1
|
||||
|
||||
#define Y_TMC2130_CS 39
|
||||
#define Y_TMC2130_DIAG 69
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 48
|
||||
//#define Y_MIN_PIN 11
|
||||
//#define Y_MAX_PIN 24
|
||||
#define Y_MIN_PIN Y_TMC2130_DIAG
|
||||
#define Y_MAX_PIN Y_TMC2130_DIAG
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN -1
|
||||
#define Y_MS2_PIN -1
|
||||
|
||||
#define Z_TMC2130_CS 67
|
||||
#define Z_TMC2130_DIAG 68
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 23
|
||||
//#define Z_MAX_PIN Z_TMC2130_DIAG
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN -1
|
||||
#define Z_MS2_PIN -1
|
||||
|
||||
#define HEATER_BED_PIN 4 //PG5
|
||||
#define TEMP_BED_PIN 2 //A2
|
||||
|
||||
#define HEATER_0_PIN 3 //PE5
|
||||
#define TEMP_0_PIN 0 //A0
|
||||
|
||||
#define HEATER_1_PIN -1
|
||||
#define TEMP_1_PIN 1 //A1
|
||||
|
||||
#define HEATER_2_PIN -1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#define TEMP_AMBIENT_PIN 6 //A6
|
||||
|
||||
#define TEMP_PINDA_PIN 3 //A3
|
||||
|
||||
#define E0_TMC2130_CS 66
|
||||
#define E0_TMC2130_DIAG 65
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN -1
|
||||
#define E0_MS2_PIN -1
|
||||
|
||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
||||
#define SDPOWER -1
|
||||
#define SDSS 53
|
||||
#define LED_PIN 13
|
||||
#define FAN_PIN 6
|
||||
#define FAN_1_PIN -1
|
||||
#define PS_ON_PIN -1
|
||||
#define KILL_PIN -1 // 80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
|
||||
|
||||
#ifdef ULTRA_LCD
|
||||
|
||||
//#define KILL_PIN 32
|
||||
|
||||
#ifdef NEWPANEL
|
||||
|
||||
#define BEEPER 84 // Beeper on AUX-4
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
|
||||
//buttons are directly attached using AUX-2
|
||||
#define BTN_EN1 72
|
||||
#define BTN_EN2 14
|
||||
#define BTN_ENC 9 // the click
|
||||
|
||||
#define SDCARDDETECT 15
|
||||
|
||||
#define TACH_0 81
|
||||
#define TACH_1 80
|
||||
|
||||
#endif //NEWPANEL
|
||||
#endif //ULTRA_LCD
|
124
Firmware/pins_Einy_0_4.h
Normal file
124
Firmware/pins_Einy_0_4.h
Normal file
|
@ -0,0 +1,124 @@
|
|||
/*****************************************************************
|
||||
* EINY Rambo 0.4a Pin Assignments
|
||||
******************************************************************/
|
||||
|
||||
#define ELECTRONICS "EINY_04a"
|
||||
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
#define TMC2130
|
||||
#define PAT9125
|
||||
|
||||
#define SWI2C // enable software i2c
|
||||
#define SWI2C_A8 // 8bit address functions
|
||||
|
||||
#define PAT9125_SWI2C
|
||||
#define PAT9125_SWI2C_SDA 20 //SDA on P3
|
||||
#define PAT9125_SWI2C_SCL 21 //SCL on P3
|
||||
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
|
||||
|
||||
//#define PAT9125_HWI2C
|
||||
|
||||
#define X_TMC2130_CS 41
|
||||
#define X_TMC2130_DIAG 64 // !!! changed from 40 (EINY03)
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 49
|
||||
#define X_MIN_PIN 12
|
||||
//#define X_MAX_PIN 30
|
||||
//#define X_MIN_PIN X_TMC2130_DIAG
|
||||
#define X_MAX_PIN X_TMC2130_DIAG
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN -1
|
||||
#define X_MS2_PIN -1
|
||||
|
||||
#define Y_TMC2130_CS 39
|
||||
#define Y_TMC2130_DIAG 69
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 48
|
||||
#define Y_MIN_PIN 11
|
||||
//#define Y_MAX_PIN 24
|
||||
//#define Y_MIN_PIN Y_TMC2130_DIAG
|
||||
#define Y_MAX_PIN Y_TMC2130_DIAG
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN -1
|
||||
#define Y_MS2_PIN -1
|
||||
|
||||
#define Z_TMC2130_CS 67
|
||||
#define Z_TMC2130_DIAG 68
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 23
|
||||
//#define Z_MAX_PIN Z_TMC2130_DIAG
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN -1
|
||||
#define Z_MS2_PIN -1
|
||||
|
||||
#define HEATER_BED_PIN 4 //PG5
|
||||
#define TEMP_BED_PIN 2 //A2
|
||||
|
||||
#define HEATER_0_PIN 3 //PE5
|
||||
#define TEMP_0_PIN 0 //A0
|
||||
|
||||
#define HEATER_1_PIN -1
|
||||
#define TEMP_1_PIN 1 //A1
|
||||
|
||||
#define HEATER_2_PIN -1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#define TEMP_AMBIENT_PIN 6 //A6
|
||||
|
||||
#define TEMP_PINDA_PIN 3 //A3
|
||||
|
||||
#define E0_TMC2130_CS 66
|
||||
#define E0_TMC2130_DIAG 65
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN -1
|
||||
#define E0_MS2_PIN -1
|
||||
|
||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
||||
#define SDPOWER -1
|
||||
#define SDSS 77
|
||||
#define LED_PIN 13
|
||||
#define FAN_PIN 6
|
||||
#define FAN_1_PIN -1
|
||||
#define PS_ON_PIN -1
|
||||
#define KILL_PIN -1 // 80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
|
||||
|
||||
#ifdef ULTRA_LCD
|
||||
|
||||
//#define KILL_PIN 32
|
||||
|
||||
#ifdef NEWPANEL
|
||||
|
||||
#define LCD_PWM_PIN 32 // lcd backlight brightnes pwm control pin
|
||||
#define LCD_PWM_MAX 0x0f // lcd pwm maximum value (0x07=64Hz, 0x0f=32Hz, 0x1f=16Hz)
|
||||
|
||||
#define BEEPER 84 // Beeper on AUX-4
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 61 // !!! changed from 18 (EINY03)
|
||||
#define LCD_PINS_D4 59 // !!! changed from 19 (EINY03)
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
|
||||
//buttons are directly attached using AUX-2
|
||||
#define BTN_EN1 72
|
||||
#define BTN_EN2 14
|
||||
#define BTN_ENC 9 // the click
|
||||
|
||||
#define SDCARDDETECT 15
|
||||
|
||||
#define TACH_0 79 // !!! changed from 81 (EINY03)
|
||||
#define TACH_1 80
|
||||
|
||||
#endif //NEWPANEL
|
||||
#endif //ULTRA_LCD
|
162
Firmware/pins_Rambo.h
Normal file
162
Firmware/pins_Rambo.h
Normal file
|
@ -0,0 +1,162 @@
|
|||
/*****************************************************************
|
||||
* Rambo Pin Assignments
|
||||
******************************************************************/
|
||||
|
||||
#define ELECTRONICS "RAMBoBig"
|
||||
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
#define FR_SENS 21
|
||||
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 48
|
||||
#define X_MIN_PIN 12
|
||||
#define X_MAX_PIN 30
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN 40
|
||||
#define X_MS2_PIN 41
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 49
|
||||
#define Y_MIN_PIN 11
|
||||
#define Y_MAX_PIN 24
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN 69
|
||||
#define Y_MS2_PIN 39
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 23
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN 68
|
||||
#define Z_MS2_PIN 67
|
||||
#define TEMP_BED_PIN 2
|
||||
#define TEMP_0_PIN 0
|
||||
#define HEATER_1_PIN 7
|
||||
#define TEMP_1_PIN 1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#ifdef SNMM
|
||||
#define E_MUX0_PIN 17
|
||||
#define E_MUX1_PIN 16
|
||||
#define E_MUX2_PIN 84
|
||||
#endif
|
||||
|
||||
#ifdef DIS
|
||||
#define D_REQUIRE 30
|
||||
#define D_DATA 20
|
||||
#define D_DATACLOCK 21
|
||||
#endif
|
||||
|
||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||
#define SDSS 53
|
||||
|
||||
#ifndef SDSUPPORT
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#endif
|
||||
|
||||
#define BEEPER 84
|
||||
|
||||
#define BTN_EN1 72
|
||||
#define BTN_EN2 14
|
||||
#define BTN_ENC 9
|
||||
|
||||
#define SDCARDDETECT 15
|
||||
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN 65
|
||||
#define E0_MS2_PIN 66
|
||||
#define LED_PIN 13
|
||||
|
||||
#ifdef THREEMM_PRINTER
|
||||
#define FAN_PIN 8
|
||||
#else
|
||||
#define FAN_PIN 6
|
||||
#endif
|
||||
|
||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||
#define SDPOWER -1
|
||||
#define HEATER_2_PIN -1
|
||||
|
||||
#define E1_STEP_PIN 33
|
||||
#define E1_DIR_PIN 42
|
||||
#define E1_ENABLE_PIN 25
|
||||
#define E1_MS1_PIN 63
|
||||
#define E1_MS2_PIN 64
|
||||
#define DIGIPOTSS_PIN 38
|
||||
#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping
|
||||
#define HEATER_0_PIN 9
|
||||
#define HEATER_BED_PIN 3
|
||||
#define PS_ON_PIN 4
|
||||
#define SDSS 53
|
||||
#ifdef ULTRA_LCD
|
||||
#define KILL_PIN 80
|
||||
#ifdef NEWPANEL
|
||||
//arduino pin which triggers an piezzo beeper
|
||||
#define BEEPER 84 // Beeper on AUX-4
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
//buttons are directly attached using AUX-2
|
||||
#define BTN_EN1 76
|
||||
#define BTN_EN2 77
|
||||
#define BTN_ENC 78 //the click
|
||||
#define BLEN_C 2
|
||||
#define BLEN_B 1
|
||||
#define BLEN_A 0
|
||||
#define SDCARDDETECT 81 // Ramps does not use this port
|
||||
//encoder rotation values
|
||||
#define encrot0 0
|
||||
#define encrot1 2
|
||||
#define encrot2 3
|
||||
#define encrot3 1
|
||||
#else //old style panel with shift register
|
||||
//arduino pin witch triggers an piezzo beeper
|
||||
#define BEEPER 84 //No Beeper added
|
||||
//buttons are attached to a shift register
|
||||
// Not wired this yet
|
||||
// #define SHIFT_CLK 38
|
||||
// #define SHIFT_LD 42
|
||||
// #define SHIFT_OUT 40
|
||||
// #define SHIFT_EN 17
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
//encoder rotation values
|
||||
#define encrot0 0
|
||||
#define encrot1 2
|
||||
#define encrot2 3
|
||||
#define encrot3 1
|
||||
//bits in the shift register that carry the buttons for:
|
||||
// left up center down right red
|
||||
#define BL_LE 7
|
||||
#define BL_UP 6
|
||||
#define BL_MI 5
|
||||
#define BL_DW 4
|
||||
#define BL_RI 3
|
||||
#define BL_ST 2
|
||||
#define BLEN_B 1
|
||||
#define BLEN_A 0
|
||||
#endif
|
||||
#endif //ULTRA_LCD
|
94
Firmware/pins_Rambo_1_0.h
Normal file
94
Firmware/pins_Rambo_1_0.h
Normal file
|
@ -0,0 +1,94 @@
|
|||
/*****************************************************************
|
||||
* Rambo mini 1.0 Pin Assignments
|
||||
******************************************************************/
|
||||
|
||||
#define ELECTRONICS "RAMBo10a"
|
||||
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
#define FR_SENS 21
|
||||
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 48
|
||||
#define X_MIN_PIN 12
|
||||
#define X_MAX_PIN 30
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN 40
|
||||
#define X_MS2_PIN 41
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 49
|
||||
#define Y_MIN_PIN 11
|
||||
#define Y_MAX_PIN 24
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN 69
|
||||
#define Y_MS2_PIN 39
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 23
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN 68
|
||||
#define Z_MS2_PIN 67
|
||||
#define TEMP_BED_PIN 2
|
||||
#define TEMP_0_PIN 0
|
||||
#define HEATER_1_PIN 7
|
||||
#define TEMP_1_PIN 1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#ifdef SNMM
|
||||
#define E_MUX0_PIN 17
|
||||
#define E_MUX1_PIN 16
|
||||
#define E_MUX2_PIN 84
|
||||
#endif
|
||||
|
||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||
#define SDSS 53
|
||||
|
||||
#ifndef SDSUPPORT
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#endif
|
||||
|
||||
#define BEEPER 78
|
||||
|
||||
#define BTN_EN1 80
|
||||
#define BTN_EN2 73
|
||||
#define BTN_ENC 21
|
||||
|
||||
#define SDCARDDETECT 72
|
||||
|
||||
#define LCD_PINS_RS 38
|
||||
#define LCD_PINS_ENABLE 5
|
||||
#define LCD_PINS_D4 14
|
||||
#define LCD_PINS_D5 15
|
||||
#define LCD_PINS_D6 32
|
||||
#define LCD_PINS_D7 31
|
||||
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN 65
|
||||
#define E0_MS2_PIN 66
|
||||
#define LED_PIN 13
|
||||
#ifdef THREEMM_PRINTER
|
||||
#define FAN_PIN 8
|
||||
#else
|
||||
#define FAN_PIN 6
|
||||
#endif
|
||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||
#define SDPOWER -1
|
||||
#define HEATER_2_PIN -1
|
||||
|
||||
#define HEATER_0_PIN 3
|
||||
#define HEATER_BED_PIN 4
|
||||
#define FAN_1_PIN -1 //6
|
||||
#define PS_ON_PIN 71
|
||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
102
Firmware/pins_Rambo_1_3.h
Normal file
102
Firmware/pins_Rambo_1_3.h
Normal file
|
@ -0,0 +1,102 @@
|
|||
/*****************************************************************
|
||||
* Rambo mini 1.3 Pin Assignments
|
||||
******************************************************************/
|
||||
|
||||
#define ELECTRONICS "RAMBo13a"
|
||||
|
||||
#define KNOWN_BOARD
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
#define FR_SENS 21
|
||||
|
||||
#define X_STEP_PIN 37
|
||||
#define X_DIR_PIN 48
|
||||
#define X_MIN_PIN 12
|
||||
#define X_MAX_PIN 30
|
||||
#define X_ENABLE_PIN 29
|
||||
#define X_MS1_PIN 40
|
||||
#define X_MS2_PIN 41
|
||||
#define Y_STEP_PIN 36
|
||||
#define Y_DIR_PIN 49
|
||||
#define Y_MIN_PIN 11
|
||||
#define Y_MAX_PIN 24
|
||||
#define Y_ENABLE_PIN 28
|
||||
#define Y_MS1_PIN 69
|
||||
#define Y_MS2_PIN 39
|
||||
#define Z_STEP_PIN 35
|
||||
#define Z_DIR_PIN 47
|
||||
#define Z_MIN_PIN 10
|
||||
#define Z_MAX_PIN 23
|
||||
#define Z_ENABLE_PIN 27
|
||||
#define Z_MS1_PIN 68
|
||||
#define Z_MS2_PIN 67
|
||||
#define TEMP_BED_PIN 2
|
||||
#define TEMP_0_PIN 0
|
||||
#define HEATER_1_PIN 7
|
||||
#define TEMP_1_PIN 1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#ifdef SNMM
|
||||
#define E_MUX0_PIN 17
|
||||
#define E_MUX1_PIN 16
|
||||
#define E_MUX2_PIN 84
|
||||
#endif
|
||||
|
||||
#ifdef DIS
|
||||
#define D_REQUIRE 30
|
||||
#define D_DATA 20
|
||||
#define D_DATACLOCK 21
|
||||
#endif
|
||||
|
||||
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
|
||||
#define SDSS 53
|
||||
|
||||
#ifndef SDSUPPORT
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#endif
|
||||
|
||||
#define BEEPER 84
|
||||
|
||||
#define BTN_EN1 72
|
||||
#define BTN_EN2 14
|
||||
#define BTN_ENC 9
|
||||
|
||||
#define SDCARDDETECT 15
|
||||
|
||||
#define LCD_PINS_RS 82
|
||||
#define LCD_PINS_ENABLE 18
|
||||
#define LCD_PINS_D4 19
|
||||
#define LCD_PINS_D5 70
|
||||
#define LCD_PINS_D6 85
|
||||
#define LCD_PINS_D7 71
|
||||
|
||||
#define E0_STEP_PIN 34
|
||||
#define E0_DIR_PIN 43
|
||||
#define E0_ENABLE_PIN 26
|
||||
#define E0_MS1_PIN 65
|
||||
#define E0_MS2_PIN 66
|
||||
#define LED_PIN 13
|
||||
|
||||
#ifdef THREEMM_PRINTER
|
||||
#define FAN_PIN 8
|
||||
#else
|
||||
#define FAN_PIN 6
|
||||
#endif
|
||||
|
||||
#define KILL_PIN -1 //80 with Smart Controller LCD
|
||||
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||
#define SDPOWER -1
|
||||
#define HEATER_2_PIN -1
|
||||
|
||||
#define HEATER_0_PIN 3
|
||||
#define HEATER_BED_PIN 4
|
||||
#define FAN_1_PIN -1 //6
|
||||
#define PS_ON_PIN 71
|
||||
#define MOTOR_CURRENT_PWM_XY_PIN 46
|
||||
#define MOTOR_CURRENT_PWM_Z_PIN 45
|
||||
#define MOTOR_CURRENT_PWM_E_PIN 44
|
|
@ -74,9 +74,8 @@ unsigned long max_acceleration_units_per_sq_second[NUM_AXIS]; // Use M201 to ove
|
|||
float minimumfeedrate;
|
||||
float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
|
||||
float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
|
||||
float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
|
||||
float max_z_jerk;
|
||||
float max_e_jerk;
|
||||
// Jerk is a maximum immediate velocity change.
|
||||
float max_jerk[NUM_AXIS];
|
||||
float mintravelfeedrate;
|
||||
unsigned long axis_steps_per_sqr_second[NUM_AXIS];
|
||||
|
||||
|
@ -93,6 +92,7 @@ matrix_3x3 plan_bed_level_matrix = {
|
|||
long position[NUM_AXIS]; //rescaled from extern when axis_steps_per_unit are changed by gcode
|
||||
static float previous_speed[NUM_AXIS]; // Speed of previous path line segment
|
||||
static float previous_nominal_speed; // Nominal speed of previous path line segment
|
||||
static float previous_safe_speed; // Exit speed limited by a jerk to full halt of a previous last segment.
|
||||
|
||||
#ifdef AUTOTEMP
|
||||
float autotemp_max=250;
|
||||
|
@ -110,6 +110,11 @@ block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion
|
|||
volatile unsigned char block_buffer_head; // Index of the next block to be pushed
|
||||
volatile unsigned char block_buffer_tail; // Index of the block to process now
|
||||
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
// Diagnostic function: Minimum number of planned moves since the last
|
||||
static uint8_t g_cntr_planner_queue_min = 0;
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
|
||||
//===========================================================================
|
||||
//=============================private variables ============================
|
||||
//===========================================================================
|
||||
|
@ -121,6 +126,12 @@ float extrude_min_temp=EXTRUDE_MINTEMP;
|
|||
static char meas_sample; //temporary variable to hold filament measurement sample
|
||||
#endif
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
float extruder_advance_k = LIN_ADVANCE_K,
|
||||
advance_ed_ratio = LIN_ADVANCE_E_D_RATIO,
|
||||
position_float[NUM_AXIS] = { 0 };
|
||||
#endif
|
||||
|
||||
// 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) {
|
||||
|
@ -171,59 +182,92 @@ FORCE_INLINE float intersection_distance(float initial_rate, float final_rate, f
|
|||
}
|
||||
}
|
||||
|
||||
// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
|
||||
#define MINIMAL_STEP_RATE 120
|
||||
|
||||
void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exit_factor) {
|
||||
unsigned long initial_rate = ceil(block->nominal_rate*entry_factor); // (step/min)
|
||||
unsigned long final_rate = ceil(block->nominal_rate*exit_factor); // (step/min)
|
||||
// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
|
||||
void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit_speed)
|
||||
{
|
||||
// These two lines are the only floating point calculations performed in this routine.
|
||||
uint32_t initial_rate = ceil(entry_speed * block->speed_factor); // (step/min)
|
||||
uint32_t final_rate = ceil(exit_speed * block->speed_factor); // (step/min)
|
||||
|
||||
// Limit minimal step rate (Otherwise the timer will overflow.)
|
||||
if(initial_rate <120) {
|
||||
initial_rate=120;
|
||||
}
|
||||
if(final_rate < 120) {
|
||||
final_rate=120;
|
||||
}
|
||||
if (initial_rate < MINIMAL_STEP_RATE)
|
||||
initial_rate = MINIMAL_STEP_RATE;
|
||||
if (initial_rate > block->nominal_rate)
|
||||
initial_rate = block->nominal_rate;
|
||||
if (final_rate < MINIMAL_STEP_RATE)
|
||||
final_rate = MINIMAL_STEP_RATE;
|
||||
if (final_rate > block->nominal_rate)
|
||||
final_rate = block->nominal_rate;
|
||||
|
||||
long acceleration = block->acceleration_st;
|
||||
int32_t accelerate_steps =
|
||||
ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration));
|
||||
int32_t decelerate_steps =
|
||||
floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -acceleration));
|
||||
|
||||
// Calculate the size of Plateau of Nominal Rate.
|
||||
int32_t plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps;
|
||||
uint32_t acceleration = block->acceleration_st;
|
||||
if (acceleration == 0)
|
||||
// Don't allow zero acceleration.
|
||||
acceleration = 1;
|
||||
// estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration)
|
||||
// (target_rate*target_rate-initial_rate*initial_rate)/(2.0*acceleration));
|
||||
uint32_t initial_rate_sqr = initial_rate*initial_rate;
|
||||
//FIXME assert that this result fits a 64bit unsigned int.
|
||||
uint32_t nominal_rate_sqr = block->nominal_rate*block->nominal_rate;
|
||||
uint32_t final_rate_sqr = final_rate*final_rate;
|
||||
uint32_t acceleration_x2 = acceleration << 1;
|
||||
// ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration));
|
||||
uint32_t accelerate_steps = (nominal_rate_sqr - initial_rate_sqr + acceleration_x2 - 1) / acceleration_x2;
|
||||
// floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -acceleration));
|
||||
uint32_t decelerate_steps = (nominal_rate_sqr - final_rate_sqr) / acceleration_x2;
|
||||
uint32_t accel_decel_steps = accelerate_steps + decelerate_steps;
|
||||
// Size of Plateau of Nominal Rate.
|
||||
uint32_t plateau_steps = 0;
|
||||
|
||||
// Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
|
||||
// have to use intersection_distance() to calculate when to abort acceleration and start braking
|
||||
// in order to reach the final_rate exactly at the end of this block.
|
||||
if (plateau_steps < 0) {
|
||||
accelerate_steps = ceil(intersection_distance(initial_rate, final_rate, acceleration, block->step_event_count));
|
||||
accelerate_steps = max(accelerate_steps,0); // Check limits due to numerical round-off
|
||||
accelerate_steps = min((uint32_t)accelerate_steps,block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero)
|
||||
plateau_steps = 0;
|
||||
if (accel_decel_steps < block->step_event_count) {
|
||||
plateau_steps = block->step_event_count - accel_decel_steps;
|
||||
} else {
|
||||
uint32_t acceleration_x4 = acceleration << 2;
|
||||
// Avoid negative numbers
|
||||
if (final_rate_sqr >= initial_rate_sqr) {
|
||||
// accelerate_steps = ceil(intersection_distance(initial_rate, final_rate, acceleration, block->step_event_count));
|
||||
// intersection_distance(float initial_rate, float final_rate, float acceleration, float distance)
|
||||
// (2.0*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/(4.0*acceleration);
|
||||
#if 0
|
||||
accelerate_steps = (block->step_event_count >> 1) + (final_rate_sqr - initial_rate_sqr + acceleration_x4 - 1 + (block->step_event_count & 1) * acceleration_x2) / acceleration_x4;
|
||||
#else
|
||||
accelerate_steps = final_rate_sqr - initial_rate_sqr + acceleration_x4 - 1;
|
||||
if (block->step_event_count & 1)
|
||||
accelerate_steps += acceleration_x2;
|
||||
accelerate_steps /= acceleration_x4;
|
||||
accelerate_steps += (block->step_event_count >> 1);
|
||||
#endif
|
||||
if (accelerate_steps > block->step_event_count)
|
||||
accelerate_steps = block->step_event_count;
|
||||
} else {
|
||||
#if 0
|
||||
decelerate_steps = (block->step_event_count >> 1) + (initial_rate_sqr - final_rate_sqr + (block->step_event_count & 1) * acceleration_x2) / acceleration_x4;
|
||||
#else
|
||||
decelerate_steps = initial_rate_sqr - final_rate_sqr;
|
||||
if (block->step_event_count & 1)
|
||||
decelerate_steps += acceleration_x2;
|
||||
decelerate_steps /= acceleration_x4;
|
||||
decelerate_steps += (block->step_event_count >> 1);
|
||||
#endif
|
||||
if (decelerate_steps > block->step_event_count)
|
||||
decelerate_steps = block->step_event_count;
|
||||
accelerate_steps = block->step_event_count - decelerate_steps;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef ADVANCE
|
||||
volatile long initial_advance = block->advance*entry_factor*entry_factor;
|
||||
volatile long final_advance = block->advance*exit_factor*exit_factor;
|
||||
#endif // ADVANCE
|
||||
|
||||
// block->accelerate_until = accelerate_steps;
|
||||
// block->decelerate_after = accelerate_steps+plateau_steps;
|
||||
CRITICAL_SECTION_START; // Fill variables used by the stepper in a critical section
|
||||
if (! block->busy) { // Don't update variables if block is busy.
|
||||
block->accelerate_until = accelerate_steps;
|
||||
block->decelerate_after = accelerate_steps+plateau_steps;
|
||||
block->initial_rate = initial_rate;
|
||||
block->final_rate = final_rate;
|
||||
#ifdef ADVANCE
|
||||
block->initial_advance = initial_advance;
|
||||
block->final_advance = final_advance;
|
||||
#endif //ADVANCE
|
||||
}
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
}
|
||||
|
||||
// Calculates the maximum allowable entry speed, when you must be able to reach target_velocity using the
|
||||
// decceleration within the allotted distance.
|
||||
|
@ -249,6 +293,27 @@ FORCE_INLINE float max_allowable_entry_speed(float decceleration, float target_v
|
|||
// the set limit. Finally it will:
|
||||
//
|
||||
// 3. Recalculate trapezoids for all blocks.
|
||||
//
|
||||
//FIXME This routine is called 15x every time a new line is added to the planner,
|
||||
// therefore it is a bottle neck and it shall be rewritten into a Fixed Point arithmetics,
|
||||
// if the CPU is found lacking computational power.
|
||||
//
|
||||
// Following sources may be used to optimize the 8-bit AVR code:
|
||||
// http://www.mikrocontroller.net/articles/AVR_Arithmetik
|
||||
// http://darcy.rsgc.on.ca/ACES/ICE4M/FixedPoint/avrfix.pdf
|
||||
//
|
||||
// https://github.com/gcc-mirror/gcc/blob/master/libgcc/config/avr/lib1funcs-fixed.S
|
||||
// https://gcc.gnu.org/onlinedocs/gcc/Fixed-Point.html
|
||||
// https://gcc.gnu.org/onlinedocs/gccint/Fixed-point-fractional-library-routines.html
|
||||
//
|
||||
// https://ucexperiment.wordpress.com/2015/04/04/arduino-s15-16-fixed-point-math-routines/
|
||||
// https://mekonik.wordpress.com/2009/03/18/arduino-avr-gcc-multiplication/
|
||||
// https://github.com/rekka/avrmultiplication
|
||||
//
|
||||
// https://people.ece.cornell.edu/land/courses/ece4760/Math/Floating_point/
|
||||
// https://courses.cit.cornell.edu/ee476/Math/
|
||||
// https://courses.cit.cornell.edu/ee476/Math/GCC644/fixedPt/multASM.S
|
||||
//
|
||||
void planner_recalculate(const float &safe_final_speed)
|
||||
{
|
||||
// Reverse pass
|
||||
|
@ -279,7 +344,7 @@ void planner_recalculate(const float &safe_final_speed)
|
|||
tail = block_index;
|
||||
// Update the number of blocks to process.
|
||||
n_blocks = (block_buffer_head + BLOCK_BUFFER_SIZE - tail) & (BLOCK_BUFFER_SIZE - 1);
|
||||
SERIAL_ECHOLNPGM("BLOCK_FLAG_START_FROM_FULL_HALT");
|
||||
// SERIAL_ECHOLNPGM("START");
|
||||
break;
|
||||
}
|
||||
// If entry speed is already at the maximum entry speed, no need to recheck. Block is cruising.
|
||||
|
@ -291,8 +356,12 @@ void planner_recalculate(const float &safe_final_speed)
|
|||
// segment and the maximum acceleration allowed for this segment.
|
||||
// If nominal length true, max junction speed is guaranteed to be reached even if decelerating to a jerk-from-zero velocity.
|
||||
// Only compute for max allowable speed if block is decelerating and nominal length is false.
|
||||
// entry_speed is uint16_t, 24 bits would be sufficient for block->acceleration and block->millimiteres, if scaled to um.
|
||||
// therefore an optimized assembly 24bit x 24bit -> 32bit multiply would be more than sufficient
|
||||
// together with an assembly 32bit->16bit sqrt function.
|
||||
current->entry_speed = ((current->flag & BLOCK_FLAG_NOMINAL_LENGTH) || current->max_entry_speed <= next->entry_speed) ?
|
||||
current->max_entry_speed :
|
||||
// min(current->max_entry_speed, sqrt(next->entry_speed*next->entry_speed+2*current->acceleration*current->millimeters));
|
||||
min(current->max_entry_speed, max_allowable_entry_speed(-current->acceleration,next->entry_speed,current->millimeters));
|
||||
current->flag |= BLOCK_FLAG_RECALCULATE;
|
||||
}
|
||||
|
@ -325,7 +394,7 @@ void planner_recalculate(const float &safe_final_speed)
|
|||
// Recalculate if current block entry or exit junction speed has changed.
|
||||
if ((prev->flag | current->flag) & BLOCK_FLAG_RECALCULATE) {
|
||||
// NOTE: Entry and exit factors always > 0 by all previous logic operations.
|
||||
calculate_trapezoid_for_block(prev, prev->entry_speed/prev->nominal_speed, current->entry_speed/prev->nominal_speed);
|
||||
calculate_trapezoid_for_block(prev, prev->entry_speed, current->entry_speed);
|
||||
// Reset current only to ensure next trapezoid is computed.
|
||||
prev->flag &= ~BLOCK_FLAG_RECALCULATE;
|
||||
}
|
||||
|
@ -338,7 +407,7 @@ void planner_recalculate(const float &safe_final_speed)
|
|||
|
||||
// Last/newest block in buffer. Exit speed is set with safe_final_speed. Always recalculated.
|
||||
current = block_buffer + prev_block_index(block_buffer_head);
|
||||
calculate_trapezoid_for_block(current, current->entry_speed/current->nominal_speed, safe_final_speed/current->nominal_speed);
|
||||
calculate_trapezoid_for_block(current, current->entry_speed, safe_final_speed);
|
||||
current->flag &= ~BLOCK_FLAG_RECALCULATE;
|
||||
|
||||
// SERIAL_ECHOLNPGM("planner_recalculate - 4");
|
||||
|
@ -348,6 +417,9 @@ 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
|
||||
previous_speed[0] = 0.0;
|
||||
previous_speed[1] = 0.0;
|
||||
previous_speed[2] = 0.0;
|
||||
|
@ -459,6 +531,96 @@ void check_axes_activity()
|
|||
#endif
|
||||
}
|
||||
|
||||
bool waiting_inside_plan_buffer_line_print_aborted = false;
|
||||
/*
|
||||
void planner_abort_soft()
|
||||
{
|
||||
// Empty the queue.
|
||||
while (blocks_queued()) plan_discard_current_block();
|
||||
// Relay to planner wait routine, that the current line shall be canceled.
|
||||
waiting_inside_plan_buffer_line_print_aborted = true;
|
||||
//current_position[i]
|
||||
}
|
||||
*/
|
||||
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
static inline void planner_update_queue_min_counter()
|
||||
{
|
||||
uint8_t new_counter = moves_planned();
|
||||
if (new_counter < g_cntr_planner_queue_min)
|
||||
g_cntr_planner_queue_min = new_counter;
|
||||
}
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
|
||||
extern volatile uint32_t step_events_completed; // The number of step events executed in the current block
|
||||
|
||||
void planner_abort_hard()
|
||||
{
|
||||
// Abort the stepper routine and flush the planner queue.
|
||||
// DISABLE_STEPPER_DRIVER_INTERRUPT
|
||||
TIMSK1 &= ~(1<<OCIE1A);
|
||||
|
||||
// Now the front-end (the Marlin_main.cpp with its current_position) is out of sync.
|
||||
// First update the planner's current position in the physical motor steps.
|
||||
position[X_AXIS] = st_get_position(X_AXIS);
|
||||
position[Y_AXIS] = st_get_position(Y_AXIS);
|
||||
position[Z_AXIS] = st_get_position(Z_AXIS);
|
||||
position[E_AXIS] = st_get_position(E_AXIS);
|
||||
|
||||
// Second update the current position of the front end.
|
||||
current_position[X_AXIS] = st_get_position_mm(X_AXIS);
|
||||
current_position[Y_AXIS] = st_get_position_mm(Y_AXIS);
|
||||
current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
|
||||
current_position[E_AXIS] = st_get_position_mm(E_AXIS);
|
||||
// Apply the mesh bed leveling correction to the Z axis.
|
||||
#ifdef MESH_BED_LEVELING
|
||||
if (mbl.active) {
|
||||
#if 1
|
||||
// Undo the bed level correction so the current Z position is reversible wrt. the machine coordinates.
|
||||
// This does not necessary mean that the Z position will be the same as linearly interpolated from the source G-code line.
|
||||
current_position[Z_AXIS] -= mbl.get_z(current_position[X_AXIS], current_position[Y_AXIS]);
|
||||
#else
|
||||
// Undo the bed level correction so that the current Z position is the same as linearly interpolated from the source G-code line.
|
||||
if (current_block == NULL || (current_block->steps_x == 0 && current_block->steps_y == 0))
|
||||
current_position[Z_AXIS] -= mbl.get_z(current_position[X_AXIS], current_position[Y_AXIS]);
|
||||
else {
|
||||
float t = float(step_events_completed) / float(current_block->step_event_count);
|
||||
float vec[3] = {
|
||||
current_block->steps_x / axis_steps_per_unit[X_AXIS],
|
||||
current_block->steps_y / axis_steps_per_unit[Y_AXIS],
|
||||
current_block->steps_z / axis_steps_per_unit[Z_AXIS]
|
||||
};
|
||||
float pos1[3], pos2[3];
|
||||
for (int8_t i = 0; i < 3; ++ i) {
|
||||
if (current_block->direction_bits & (1<<i))
|
||||
vec[i] = - vec[i];
|
||||
pos1[i] = current_position[i] - vec[i] * t;
|
||||
pos2[i] = current_position[i] + vec[i] * (1.f - t);
|
||||
}
|
||||
pos1[Z_AXIS] -= mbl.get_z(pos1[X_AXIS], pos1[Y_AXIS]);
|
||||
pos2[Z_AXIS] -= mbl.get_z(pos2[X_AXIS], pos2[Y_AXIS]);
|
||||
current_position[Z_AXIS] = pos1[Z_AXIS] * t + pos2[Z_AXIS] * (1.f - t);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
// Clear the planner queue.
|
||||
quickStop();
|
||||
|
||||
// Apply inverse world correction matrix.
|
||||
machine2world(current_position[X_AXIS], current_position[Y_AXIS]);
|
||||
memcpy(destination, current_position, sizeof(destination));
|
||||
|
||||
// Resets planner junction speeds. Assumes start from rest.
|
||||
previous_nominal_speed = 0.0;
|
||||
previous_speed[0] = 0.0;
|
||||
previous_speed[1] = 0.0;
|
||||
previous_speed[2] = 0.0;
|
||||
previous_speed[3] = 0.0;
|
||||
|
||||
// Relay to planner wait routine, that the current line shall be canceled.
|
||||
waiting_inside_plan_buffer_line_print_aborted = true;
|
||||
}
|
||||
|
||||
float junction_deviation = 0.1;
|
||||
// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in
|
||||
|
@ -471,13 +633,26 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
|||
|
||||
// If the buffer is full: good! That means we are well ahead of the robot.
|
||||
// Rest here until there is room in the buffer.
|
||||
while(block_buffer_tail == next_buffer_head)
|
||||
{
|
||||
manage_heater();
|
||||
// Vojtech: Don't disable motors inside the planner!
|
||||
manage_inactivity(false);
|
||||
lcd_update();
|
||||
if (block_buffer_tail == next_buffer_head) {
|
||||
waiting_inside_plan_buffer_line_print_aborted = false;
|
||||
do {
|
||||
manage_heater();
|
||||
// Vojtech: Don't disable motors inside the planner!
|
||||
manage_inactivity(false);
|
||||
lcd_update();
|
||||
} while (block_buffer_tail == next_buffer_head);
|
||||
if (waiting_inside_plan_buffer_line_print_aborted) {
|
||||
// Inside the lcd_update() routine the print has been aborted.
|
||||
// Cancel the print, do not plan the current line this routine is waiting on.
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
planner_update_queue_min_counter();
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
return;
|
||||
}
|
||||
}
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
planner_update_queue_min_counter();
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
|
||||
|
@ -543,12 +718,22 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
|||
target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
|
||||
#endif // ENABLE_MESH_BED_LEVELING
|
||||
target[E_AXIS] = lround(e*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
|
||||
position_float[E_AXIS] = e;
|
||||
de_float = 0;
|
||||
#endif
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(MSG_ERR_COLD_EXTRUDE_STOP);
|
||||
}
|
||||
|
@ -557,6 +742,10 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
|||
if(labs(target[E_AXIS]-position[E_AXIS])>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
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(MSG_ERR_LONG_EXTRUDE_STOP);
|
||||
}
|
||||
|
@ -567,6 +756,9 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
|||
// Prepare to set up new block
|
||||
block_t *block = &block_buffer[block_buffer_head];
|
||||
|
||||
// Set sdlen for calculating sd position
|
||||
block->sdlen = 0;
|
||||
|
||||
// Mark block as not busy (Not executed by the stepper interrupt, could be still tinkered with.)
|
||||
block->busy = false;
|
||||
|
||||
|
@ -583,14 +775,20 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
|
|||
#endif
|
||||
block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
|
||||
block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
|
||||
block->steps_e *= volumetric_multiplier[active_extruder];
|
||||
block->steps_e *= extrudemultiply;
|
||||
block->steps_e /= 100;
|
||||
if (volumetric_multiplier[active_extruder] != 1.f)
|
||||
block->steps_e *= volumetric_multiplier[active_extruder];
|
||||
if (extrudemultiply != 100) {
|
||||
block->steps_e *= extrudemultiply;
|
||||
block->steps_e /= 100;
|
||||
}
|
||||
block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
|
||||
|
||||
// Bail if this is a zero-length block
|
||||
if (block->step_event_count <= dropsegments)
|
||||
{
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
planner_update_queue_min_counter();
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -815,6 +1013,8 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
}
|
||||
|
||||
// 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.
|
||||
float steps_per_mm = block->step_event_count/block->millimeters;
|
||||
if(block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)
|
||||
{
|
||||
|
@ -834,88 +1034,62 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
if(((float)block->acceleration_st * (float)block->steps_z / (float)block->step_event_count ) > axis_steps_per_sqr_second[Z_AXIS])
|
||||
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
|
||||
}
|
||||
// Acceleration of the segment, in mm/sec^2
|
||||
block->acceleration = block->acceleration_st / steps_per_mm;
|
||||
|
||||
#if 0
|
||||
// Oversample diagonal movements by a power of 2 up to 8x
|
||||
// to achieve more accurate diagonal movements.
|
||||
uint8_t bresenham_oversample = 1;
|
||||
for (uint8_t i = 0; i < 3; ++ i) {
|
||||
if (block->nominal_rate >= 5000) // 5kHz
|
||||
break;
|
||||
block->nominal_rate << 1;
|
||||
bresenham_oversample << 1;
|
||||
block->step_event_count << 1;
|
||||
}
|
||||
if (bresenham_oversample > 1)
|
||||
// Lower the acceleration steps/sec^2 to account for the oversampling.
|
||||
block->acceleration_st = (block->acceleration_st + (bresenham_oversample >> 1)) / bresenham_oversample;
|
||||
#endif
|
||||
|
||||
block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
|
||||
|
||||
#if 0 // Use old jerk for now
|
||||
// Compute path unit vector
|
||||
double unit_vec[3];
|
||||
|
||||
unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters;
|
||||
unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters;
|
||||
unit_vec[Z_AXIS] = delta_mm[Z_AXIS]*inverse_millimeters;
|
||||
|
||||
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
|
||||
// Let a circle be tangent to both previous and current path line segments, where the junction
|
||||
// deviation is defined as the distance from the junction to the closest edge of the circle,
|
||||
// colinear with the circle center. The circular segment joining the two paths represents the
|
||||
// path of centripetal acceleration. Solve for max velocity based on max acceleration about the
|
||||
// radius of the circle, defined indirectly by junction deviation. This may be also viewed as
|
||||
// path width or max_jerk in the previous grbl version. This approach does not actually deviate
|
||||
// from path, but used as a robust way to compute cornering speeds, as it takes into account the
|
||||
// nonlinearities of both the junction angle and junction velocity.
|
||||
double vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed
|
||||
|
||||
// Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles.
|
||||
if ((block_buffer_head != block_buffer_tail) && (previous_nominal_speed > 0.0)) {
|
||||
// Compute cosine of angle between previous and current path. (prev_unit_vec is negative)
|
||||
// NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity.
|
||||
double cos_theta = - previous_unit_vec[X_AXIS] * unit_vec[X_AXIS]
|
||||
- previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS]
|
||||
- previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ;
|
||||
|
||||
// Skip and use default max junction speed for 0 degree acute junction.
|
||||
if (cos_theta < 0.95) {
|
||||
vmax_junction = min(previous_nominal_speed,block->nominal_speed);
|
||||
// Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
|
||||
if (cos_theta > -0.95) {
|
||||
// Compute maximum junction velocity based on maximum acceleration and junction deviation
|
||||
double sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive.
|
||||
vmax_junction = min(vmax_junction,
|
||||
sqrt(block->acceleration * junction_deviation * sin_theta_d2/(1.0-sin_theta_d2)) );
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
// Start with a safe speed.
|
||||
//Vojtech: This code tries to limit the initial jerk to half of the maximum jerk value.
|
||||
//The code is not quite correct. It is pessimistic as it shall limit a projection of the jerk into each axis,
|
||||
//but when the current code clamps, it clamps as if the movement is done in a single axis only.
|
||||
float vmax_junction = max_xy_jerk/2.f;
|
||||
if(fabs(current_speed[Z_AXIS]) > max_z_jerk/2.f)
|
||||
vmax_junction = min(vmax_junction, max_z_jerk/2.f);
|
||||
if(fabs(current_speed[E_AXIS]) > max_e_jerk/2.f)
|
||||
vmax_junction = min(vmax_junction, max_e_jerk/2.f);
|
||||
vmax_junction = min(vmax_junction, block->nominal_speed);
|
||||
// Safe speed is the speed, from which the machine may halt to stop immediately.
|
||||
float safe_speed = vmax_junction;
|
||||
float safe_speed = block->nominal_speed;
|
||||
bool limited = false;
|
||||
for (uint8_t axis = 0; axis < 4; ++ axis) {
|
||||
float jerk = fabs(current_speed[axis]);
|
||||
if (jerk > max_jerk[axis]) {
|
||||
// The actual jerk is lower, if it has been limited by the XY jerk.
|
||||
if (limited) {
|
||||
// Spare one division by a following gymnastics:
|
||||
// Instead of jerk *= safe_speed / block->nominal_speed,
|
||||
// multiply max_jerk[axis] by the divisor.
|
||||
jerk *= safe_speed;
|
||||
float mjerk = max_jerk[axis] * block->nominal_speed;
|
||||
if (jerk > mjerk) {
|
||||
safe_speed *= mjerk / jerk;
|
||||
limited = true;
|
||||
}
|
||||
} else {
|
||||
safe_speed = max_jerk[axis];
|
||||
limited = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Reset the block flag.
|
||||
block->flag = 0;
|
||||
|
||||
// Initial limit on the segment entry velocity.
|
||||
float vmax_junction;
|
||||
|
||||
//FIXME Vojtech: Why only if at least two lines are planned in the queue?
|
||||
// Is it because we don't want to tinker with the first buffer line, which
|
||||
// is likely to be executed by the stepper interrupt routine soon?
|
||||
if (moves_queued > 1 && previous_nominal_speed > 0.0001f) {
|
||||
#if 1
|
||||
float jerk;
|
||||
{
|
||||
float dx = current_speed[X_AXIS]-previous_speed[X_AXIS];
|
||||
float dy = current_speed[Y_AXIS]-previous_speed[Y_AXIS];
|
||||
jerk = sqrt(dx*dx+dy*dy);
|
||||
}
|
||||
float vmax_junction_factor = 1.0;
|
||||
// if((fabs(previous_speed[X_AXIS]) > 0.0001) || (fabs(previous_speed[Y_AXIS]) > 0.0001)) {
|
||||
vmax_junction = block->nominal_speed;
|
||||
// }
|
||||
if (jerk > max_xy_jerk)
|
||||
vmax_junction_factor = max_xy_jerk/jerk;
|
||||
jerk = fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]);
|
||||
if (jerk > max_z_jerk)
|
||||
vmax_junction_factor = min(vmax_junction_factor, max_z_jerk/jerk);
|
||||
jerk = fabs(current_speed[E_AXIS] - previous_speed[E_AXIS]);
|
||||
if (jerk > max_e_jerk)
|
||||
vmax_junction_factor = min(vmax_junction_factor, max_e_jerk/jerk);
|
||||
//FIXME Vojtech: Why is this asymmetric in regard to the previous nominal speed and the current nominal speed?
|
||||
vmax_junction = min(previous_nominal_speed, vmax_junction * vmax_junction_factor); // Limit speed to max previous speed
|
||||
#else
|
||||
// Estimate a maximum velocity allowed at a joint of two successive segments.
|
||||
// If this maximum velocity allowed is lower than the minimum of the entry / exit safe velocities,
|
||||
// then the machine is not coasting anymore and the safe entry / exit velocities shall be used.
|
||||
|
@ -926,72 +1100,54 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
// Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting.
|
||||
vmax_junction = prev_speed_larger ? block->nominal_speed : previous_nominal_speed;
|
||||
// Factor to multiply the previous / current nominal velocities to get componentwise limited velocities.
|
||||
float v_factor_exit = prev_speed_larger ? smaller_speed_factor : 1.f;
|
||||
float v_factor_entry = prev_speed_larger ? 1.f : smaller_speed_factor;
|
||||
// First limit the jerk in the XY plane.
|
||||
float jerk;
|
||||
{
|
||||
// Estimate the jerk as if the entry / exit velocity of the two successive segment was limited to the minimum of their nominal velocities.
|
||||
// If coasting, then the segment transition velocity will define the exit / entry velocities of the successive segments
|
||||
// and the jerk defined by the following formula will be always lower.
|
||||
float dx = prev_speed_larger ? (current_speed[X_AXIS] - smaller_speed_factor * previous_speed[X_AXIS]) : (smaller_speed_factor * current_speed[X_AXIS] - previous_speed[X_AXIS]);
|
||||
float dy = prev_speed_larger ? (current_speed[Y_AXIS] - smaller_speed_factor * previous_speed[Y_AXIS]) : (smaller_speed_factor * current_speed[Y_AXIS] - previous_speed[Y_AXIS]);
|
||||
jerk = sqrt(dx*dx+dy*dy);
|
||||
}
|
||||
if (jerk > max_xy_jerk) {
|
||||
// Limit the entry / exit velocities to respect the XY jerk limits.
|
||||
v_factor_exit = v_factor_entry = max_xy_jerk / jerk;
|
||||
float v_factor = 1.f;
|
||||
limited = false;
|
||||
// Now limit the jerk in all axes.
|
||||
for (uint8_t axis = 0; axis < 4; ++ axis) {
|
||||
// Limit an axis. We have to differentiate coasting from the reversal of an axis movement, or a full stop.
|
||||
float v_exit = previous_speed[axis];
|
||||
float v_entry = current_speed [axis];
|
||||
if (prev_speed_larger)
|
||||
v_factor_exit *= smaller_speed_factor;
|
||||
else
|
||||
v_factor_entry *= smaller_speed_factor;
|
||||
v_exit *= smaller_speed_factor;
|
||||
if (limited) {
|
||||
v_exit *= v_factor;
|
||||
v_entry *= v_factor;
|
||||
}
|
||||
// Calculate the jerk depending on whether the axis is coasting in the same direction or reversing a direction.
|
||||
float jerk =
|
||||
(v_exit > v_entry) ?
|
||||
((v_entry > 0.f || v_exit < 0.f) ?
|
||||
// coasting
|
||||
(v_exit - v_entry) :
|
||||
// axis reversal
|
||||
max(v_exit, - v_entry)) :
|
||||
// v_exit <= v_entry
|
||||
((v_entry < 0.f || v_exit > 0.f) ?
|
||||
// coasting
|
||||
(v_entry - v_exit) :
|
||||
// axis reversal
|
||||
max(- v_exit, v_entry));
|
||||
if (jerk > max_jerk[axis]) {
|
||||
v_factor *= max_jerk[axis] / jerk;
|
||||
limited = true;
|
||||
}
|
||||
}
|
||||
// Now limit the Z and E axes. We have to differentiate coasting from the reversal of an axis movement, or a full stop.
|
||||
float v_exit = previous_speed[Z_AXIS] * v_factor_exit;
|
||||
float v_entry = current_speed [Z_AXIS] * v_factor_entry;
|
||||
jerk = (v_exit > v_entry) ?
|
||||
((v_entry > 0.f || v_exit < 0.f) ?
|
||||
// coasting
|
||||
(v_exit - v_entry) :
|
||||
// axis reversal
|
||||
max(v_exit, - v_entry)) :
|
||||
// v_exit <= v_entry
|
||||
((v_entry < 0.f || v_exit > 0.f) ?
|
||||
// coasting
|
||||
(v_entry - v_exit) :
|
||||
// axis reversal
|
||||
max(- v_exit, v_entry));
|
||||
if (jerk > max_z_jerk / 2.f) {
|
||||
float c = (max_z_jerk / 2.f) / jerk;
|
||||
v_factor_exit *= c;
|
||||
v_factor_entry *= c;
|
||||
if (limited)
|
||||
vmax_junction *= v_factor;
|
||||
// Now the transition velocity is known, which maximizes the shared exit / entry velocity while
|
||||
// respecting the jerk factors, it may be possible, that applying separate safe exit / entry velocities will achieve faster prints.
|
||||
float vmax_junction_threshold = vmax_junction * 0.99f;
|
||||
if (previous_safe_speed > vmax_junction_threshold && safe_speed > vmax_junction_threshold) {
|
||||
// Not coasting. The machine will stop and start the movements anyway,
|
||||
// better to start the segment from start.
|
||||
block->flag |= BLOCK_FLAG_START_FROM_FULL_HALT;
|
||||
vmax_junction = safe_speed;
|
||||
}
|
||||
// Limit the E axis.
|
||||
v_exit = previous_speed[E_AXIS] * v_factor_exit;
|
||||
v_entry = current_speed [E_AXIS] * v_factor_entry;
|
||||
jerk = (v_exit > v_entry) ?
|
||||
((v_entry > 0.f || v_exit < 0.f) ?
|
||||
// coasting
|
||||
(v_exit - v_entry) :
|
||||
// axis reversal
|
||||
max(v_exit, - v_entry)) :
|
||||
// v_exit <= v_entry
|
||||
((v_entry < 0.f || v_exit > 0.f) ?
|
||||
// coasting
|
||||
(v_entry - v_exit) :
|
||||
// axis reversal
|
||||
max(- v_exit, v_entry));
|
||||
if (jerk > max_e_jerk / 2.f) {
|
||||
float c = (max_e_jerk / 2.f) / jerk;
|
||||
v_factor_exit *= c;
|
||||
v_factor_entry *= c;
|
||||
}
|
||||
|
||||
// Now the transition velocity is known as nominal * v_factor. Compare the transition velocity against the "safe" velocoties.
|
||||
// If the transition velocity is below the exit / enter safe velocity, the machine is no more cruising, therefore
|
||||
// the safe velocities shall be used.
|
||||
#endif
|
||||
} else {
|
||||
block->flag |= BLOCK_FLAG_START_FROM_FULL_HALT;
|
||||
vmax_junction = safe_speed;
|
||||
}
|
||||
|
||||
// Max entry speed of this block equals the max exit speed of the previous block.
|
||||
block->max_entry_speed = vmax_junction;
|
||||
|
||||
|
@ -1008,41 +1164,47 @@ Having the real displacement of the head, we can calculate the total movement le
|
|||
// the reverse and forward planners, the corresponding block junction speed will always be at the
|
||||
// the maximum junction speed and may always be ignored for any speed reduction checks.
|
||||
// Always calculate trapezoid for new block
|
||||
block->flag = (block->nominal_speed <= v_allowable) ? (BLOCK_FLAG_NOMINAL_LENGTH | BLOCK_FLAG_RECALCULATE) : BLOCK_FLAG_RECALCULATE;
|
||||
block->flag |= (block->nominal_speed <= v_allowable) ? (BLOCK_FLAG_NOMINAL_LENGTH | BLOCK_FLAG_RECALCULATE) : BLOCK_FLAG_RECALCULATE;
|
||||
|
||||
// Update previous path unit_vector and nominal speed
|
||||
memcpy(previous_speed, current_speed, sizeof(previous_speed)); // previous_speed[] = current_speed[]
|
||||
previous_nominal_speed = block->nominal_speed;
|
||||
previous_safe_speed = safe_speed;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
|
||||
#ifdef ADVANCE
|
||||
// Calculate advance rate
|
||||
if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
|
||||
block->advance_rate = 0;
|
||||
block->advance = 0;
|
||||
}
|
||||
else {
|
||||
long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
|
||||
float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) *
|
||||
(current_speed[E_AXIS] * current_speed[E_AXIS] * EXTRUSION_AREA * EXTRUSION_AREA)*256;
|
||||
block->advance = advance;
|
||||
if(acc_dist == 0) {
|
||||
block->advance_rate = 0;
|
||||
}
|
||||
else {
|
||||
block->advance_rate = advance / (float)acc_dist;
|
||||
}
|
||||
}
|
||||
/*
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOPGM("advance :");
|
||||
SERIAL_ECHO(block->advance/256.0);
|
||||
SERIAL_ECHOPGM("advance rate :");
|
||||
SERIAL_ECHOLN(block->advance_rate/256.0);
|
||||
*/
|
||||
#endif // ADVANCE
|
||||
|
||||
calculate_trapezoid_for_block(block, block->entry_speed/block->nominal_speed, safe_speed/block->nominal_speed);
|
||||
//
|
||||
// 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
|
||||
&& (block->steps_x || block->steps_y)
|
||||
&& extruder_advance_k
|
||||
&& (uint32_t)block->steps_e != block->step_event_count
|
||||
&& 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)
|
||||
* 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);
|
||||
|
||||
// Move the buffer head. From now the block may be picked up by the stepper interrupt controller.
|
||||
block_buffer_head = next_buffer_head;
|
||||
|
@ -1050,12 +1212,26 @@ 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
|
||||
position_float[X_AXIS] = x;
|
||||
position_float[Y_AXIS] = y;
|
||||
position_float[Z_AXIS] = z;
|
||||
position_float[E_AXIS] = e;
|
||||
#endif
|
||||
|
||||
// Recalculate the trapezoids to maximize speed at the segment transitions while respecting
|
||||
// the machine limits (maximum acceleration and maximum jerk).
|
||||
// This runs asynchronously with the stepper interrupt controller, which may
|
||||
// interfere with the process.
|
||||
planner_recalculate(safe_speed);
|
||||
|
||||
// SERIAL_ECHOPGM("Q");
|
||||
// SERIAL_ECHO(int(moves_planned()));
|
||||
// SERIAL_ECHOLNPGM("");
|
||||
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
planner_update_queue_min_counter();
|
||||
#endif /* PLANNER_DIAGNOSTIC */
|
||||
st_wake_up();
|
||||
}
|
||||
|
||||
|
@ -1081,6 +1257,7 @@ void plan_set_position(float x, float y, float z, const float &e)
|
|||
#endif // ENABLE_AUTO_BED_LEVELING
|
||||
|
||||
// Apply the machine correction matrix.
|
||||
if (world2machine_correction_mode != WORLD2MACHINE_CORRECTION_NONE)
|
||||
{
|
||||
float tmpx = x;
|
||||
float tmpy = y;
|
||||
|
@ -1091,15 +1268,19 @@ void plan_set_position(float x, float y, float z, const float &e)
|
|||
position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
|
||||
position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
|
||||
#ifdef MESH_BED_LEVELING
|
||||
if (mbl.active){
|
||||
position[Z_AXIS] = lround((z+mbl.get_z(x, y))*axis_steps_per_unit[Z_AXIS]);
|
||||
}else{
|
||||
position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
|
||||
}
|
||||
position[Z_AXIS] = mbl.active ?
|
||||
lround((z+mbl.get_z(x, y))*axis_steps_per_unit[Z_AXIS]) :
|
||||
lround(z*axis_steps_per_unit[Z_AXIS]);
|
||||
#else
|
||||
position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);
|
||||
#endif // ENABLE_MESH_BED_LEVELING
|
||||
position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
|
||||
position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
|
||||
#ifdef LIN_ADVANCE
|
||||
position_float[X_AXIS] = x;
|
||||
position_float[Y_AXIS] = y;
|
||||
position_float[Z_AXIS] = z;
|
||||
position_float[E_AXIS] = e;
|
||||
#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;
|
||||
|
@ -1111,12 +1292,18 @@ 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*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)
|
||||
{
|
||||
#ifdef LIN_ADVANCE
|
||||
position_float[E_AXIS] = e;
|
||||
#endif
|
||||
position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);
|
||||
st_set_e_position(position[E_AXIS]);
|
||||
}
|
||||
|
@ -1136,3 +1323,42 @@ void reset_acceleration_rates()
|
|||
axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
|
||||
}
|
||||
}
|
||||
unsigned char number_of_blocks() {
|
||||
return (block_buffer_head + BLOCK_BUFFER_SIZE - block_buffer_tail) & (BLOCK_BUFFER_SIZE - 1);
|
||||
}
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
uint8_t planner_queue_min()
|
||||
{
|
||||
return g_cntr_planner_queue_min;
|
||||
}
|
||||
|
||||
void planner_queue_min_reset()
|
||||
{
|
||||
g_cntr_planner_queue_min = moves_planned();
|
||||
}
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
|
||||
void planner_add_sd_length(uint16_t sdlen)
|
||||
{
|
||||
if (block_buffer_head != block_buffer_tail) {
|
||||
// The planner buffer is not empty. Get the index of the last buffer line entered,
|
||||
// which is (block_buffer_head - 1) modulo BLOCK_BUFFER_SIZE.
|
||||
block_buffer[prev_block_index(block_buffer_head)].sdlen += sdlen;
|
||||
} else {
|
||||
// There is no line stored in the planner buffer, which means the last command does not need to be revertible,
|
||||
// at a power panic, so the length of this command may be forgotten.
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t planner_calc_sd_length()
|
||||
{
|
||||
unsigned char _block_buffer_head = block_buffer_head;
|
||||
unsigned char _block_buffer_tail = block_buffer_tail;
|
||||
uint16_t sdlen = 0;
|
||||
while (_block_buffer_head != _block_buffer_tail)
|
||||
{
|
||||
sdlen += block_buffer[_block_buffer_tail].sdlen;
|
||||
_block_buffer_tail = (_block_buffer_tail + 1) & (BLOCK_BUFFER_SIZE - 1);
|
||||
}
|
||||
return sdlen;
|
||||
}
|
||||
|
|
|
@ -37,12 +37,9 @@ enum BlockFlag {
|
|||
// Planner flag for nominal speed always reached. That means, the segment is long enough, that the nominal speed
|
||||
// may be reached if accelerating from a safe speed (in the regard of jerking from zero speed).
|
||||
BLOCK_FLAG_NOMINAL_LENGTH = 2,
|
||||
// If set, the machine will stop to a full halt at the end of this block,
|
||||
// respecting the maximum allowed jerk.
|
||||
BLOCK_FLAG_FULL_HALT_AT_END = 4,
|
||||
// If set, the machine will start from a halt at the start of this block,
|
||||
// respecting the maximum allowed jerk.
|
||||
BLOCK_FLAG_START_FROM_FULL_HALT = 8,
|
||||
BLOCK_FLAG_START_FROM_FULL_HALT = 4,
|
||||
};
|
||||
|
||||
// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in
|
||||
|
@ -58,12 +55,6 @@ typedef struct {
|
|||
// accelerate_until and decelerate_after are set by calculate_trapezoid_for_block() and they need to be synchronized with the stepper interrupt controller.
|
||||
long accelerate_until; // The index of the step event on which to stop acceleration
|
||||
long decelerate_after; // The index of the step event on which to start decelerating
|
||||
#ifdef ADVANCE
|
||||
long advance_rate;
|
||||
volatile long initial_advance;
|
||||
volatile long final_advance;
|
||||
float advance;
|
||||
#endif
|
||||
|
||||
// Fields used by the motion planner to manage acceleration
|
||||
// float speed_x, speed_y, speed_z, speed_e; // Nominal mm/sec for each axis
|
||||
|
@ -85,14 +76,31 @@ typedef struct {
|
|||
|
||||
// Settings for the trapezoid generator (runs inside an interrupt handler).
|
||||
// Changing the following values in the planner needs to be synchronized with the interrupt handler by disabling the interrupts.
|
||||
//FIXME nominal_rate, initial_rate and final_rate are limited to uint16_t by MultiU24X24toH16 in the stepper interrupt anyway!
|
||||
unsigned long nominal_rate; // The nominal step rate for this block in step_events/sec
|
||||
unsigned long initial_rate; // The jerk-adjusted step rate at start of block
|
||||
unsigned long final_rate; // The minimal rate at exit
|
||||
unsigned long acceleration_st; // acceleration steps/sec^2
|
||||
//FIXME does it have to be unsigned long? Probably uint8_t would be just fine.
|
||||
unsigned long fan_speed;
|
||||
volatile char busy;
|
||||
|
||||
|
||||
// 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
|
||||
#endif
|
||||
|
||||
uint16_t sdlen;
|
||||
} block_t;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
extern float extruder_advance_k, advance_ed_ratio;
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
// this holds the required transform to compensate for bed level
|
||||
extern matrix_3x3 plan_bed_level_matrix;
|
||||
|
@ -135,9 +143,8 @@ extern unsigned long max_acceleration_units_per_sq_second[NUM_AXIS]; // Use M201
|
|||
extern float minimumfeedrate;
|
||||
extern float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
|
||||
extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
|
||||
extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
|
||||
extern float max_z_jerk;
|
||||
extern float max_e_jerk;
|
||||
// Jerk is a maximum immediate velocity change.
|
||||
extern float max_jerk[NUM_AXIS];
|
||||
extern float mintravelfeedrate;
|
||||
extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
|
||||
|
||||
|
@ -152,7 +159,11 @@ extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
|
|||
|
||||
|
||||
extern block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instfructions
|
||||
extern volatile unsigned char block_buffer_head; // Index of the next block to be pushed
|
||||
// Index of the next block to be pushed into the planner queue.
|
||||
extern volatile unsigned char block_buffer_head;
|
||||
// Index of the first block in the planner queue.
|
||||
// This is the block, which is being currently processed by the stepper routine,
|
||||
// or which is first to be processed by the stepper routine.
|
||||
extern volatile unsigned char block_buffer_tail;
|
||||
// Called when the current block is no longer needed. Discards the block and makes the memory
|
||||
// available for new blocks.
|
||||
|
@ -163,7 +174,10 @@ FORCE_INLINE void plan_discard_current_block()
|
|||
}
|
||||
}
|
||||
|
||||
// Gets the current block. Returns NULL if buffer empty
|
||||
// Gets the current block. This is the block to be exectuted by the stepper routine.
|
||||
// Mark this block as busy, so its velocities and acceperations will be no more recalculated
|
||||
// by the planner routine.
|
||||
// Returns NULL if buffer empty
|
||||
FORCE_INLINE block_t *plan_get_current_block()
|
||||
{
|
||||
if (block_buffer_head == block_buffer_tail) {
|
||||
|
@ -175,16 +189,44 @@ FORCE_INLINE block_t *plan_get_current_block()
|
|||
}
|
||||
|
||||
// Returns true if the buffer has a queued block, false otherwise
|
||||
FORCE_INLINE bool blocks_queued() { return (block_buffer_head != block_buffer_tail); }
|
||||
FORCE_INLINE bool blocks_queued() {
|
||||
return (block_buffer_head != block_buffer_tail);
|
||||
}
|
||||
|
||||
//return the nr of buffered moves
|
||||
FORCE_INLINE uint8_t moves_planned() {
|
||||
return (block_buffer_head + BLOCK_BUFFER_SIZE - block_buffer_tail) & (BLOCK_BUFFER_SIZE - 1);
|
||||
}
|
||||
|
||||
FORCE_INLINE bool planner_queue_full() {
|
||||
unsigned char next_block_index = block_buffer_head;
|
||||
if (++ next_block_index == BLOCK_BUFFER_SIZE)
|
||||
next_block_index = 0;
|
||||
return block_buffer_tail == next_block_index;
|
||||
}
|
||||
|
||||
// Abort the stepper routine, clean up the block queue,
|
||||
// wait for the steppers to stop,
|
||||
// update planner's current position and the current_position of the front end.
|
||||
extern void planner_abort_hard();
|
||||
|
||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||
void set_extrude_min_temp(float temp);
|
||||
#endif
|
||||
|
||||
void reset_acceleration_rates();
|
||||
#endif
|
||||
|
||||
unsigned char number_of_blocks();
|
||||
|
||||
// #define PLANNER_DIAGNOSTICS
|
||||
#ifdef PLANNER_DIAGNOSTICS
|
||||
// Diagnostic functions to display planner buffer underflow on the display.
|
||||
extern uint8_t planner_queue_min();
|
||||
// Diagnostic function: Reset the minimum planner segments.
|
||||
extern void planner_queue_min_reset();
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
|
||||
extern void planner_add_sd_length(uint16_t sdlen);
|
||||
|
||||
extern uint16_t planner_calc_sd_length();
|
||||
|
|
|
@ -32,14 +32,25 @@
|
|||
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
#ifdef TMC2130
|
||||
#include "tmc2130.h"
|
||||
#endif //TMC2130
|
||||
|
||||
#ifdef PAT9125
|
||||
#include "fsensor.h"
|
||||
int fsensor_counter = 0; //counter for e-steps
|
||||
#endif //PAT9125
|
||||
|
||||
//===========================================================================
|
||||
//=============================public variables ============================
|
||||
//===========================================================================
|
||||
block_t *current_block; // A pointer to the block currently being traced
|
||||
|
||||
|
||||
bool x_min_endstop = false;
|
||||
bool x_max_endstop = false;
|
||||
bool y_min_endstop = false;
|
||||
bool y_max_endstop = false;
|
||||
bool z_min_endstop = false;
|
||||
bool z_max_endstop = false;
|
||||
//===========================================================================
|
||||
//=============================private variables ============================
|
||||
//===========================================================================
|
||||
|
@ -47,22 +58,17 @@ block_t *current_block; // A pointer to the block currently being traced
|
|||
|
||||
// Variables used by The Stepper Driver Interrupt
|
||||
static unsigned char out_bits; // The next stepping-bits to be output
|
||||
static long counter_x, // Counter variables for the bresenham line tracer
|
||||
counter_y,
|
||||
counter_z,
|
||||
counter_e;
|
||||
volatile static unsigned long step_events_completed; // The number of step events executed in the current block
|
||||
#ifdef ADVANCE
|
||||
static long advance_rate, advance, final_advance = 0;
|
||||
static long old_advance = 0;
|
||||
static long e_steps[3];
|
||||
#endif
|
||||
static long acceleration_time, deceleration_time;
|
||||
static int32_t counter_x, // Counter variables for the bresenham line tracer
|
||||
counter_y,
|
||||
counter_z,
|
||||
counter_e;
|
||||
volatile uint32_t step_events_completed; // The number of step events executed in the current block
|
||||
static int32_t acceleration_time, deceleration_time;
|
||||
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
|
||||
static unsigned short acc_step_rate; // needed for deccelaration start point
|
||||
static char step_loops;
|
||||
static unsigned short OCR1A_nominal;
|
||||
static unsigned short step_loops_nominal;
|
||||
static uint16_t acc_step_rate; // needed for deccelaration start point
|
||||
static uint8_t step_loops;
|
||||
static uint16_t OCR1A_nominal;
|
||||
static uint8_t step_loops_nominal;
|
||||
|
||||
volatile long endstops_trigsteps[3]={0,0,0};
|
||||
volatile long endstops_stepsTotal,endstops_stepsDone;
|
||||
|
@ -86,19 +92,44 @@ static bool old_z_min_endstop=false;
|
|||
static bool old_z_max_endstop=false;
|
||||
|
||||
static bool check_endstops = true;
|
||||
|
||||
static bool check_z_endstop = false;
|
||||
|
||||
int8_t SilentMode;
|
||||
int8_t SilentMode = 0;
|
||||
|
||||
volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
|
||||
volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
|
||||
|
||||
uint8_t LastStepMask = 0;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
|
||||
uint16_t ADV_NEVER = 65535;
|
||||
|
||||
static uint16_t nextMainISR = 0;
|
||||
static uint16_t nextAdvanceISR = ADV_NEVER;
|
||||
static uint16_t eISR_Rate = ADV_NEVER;
|
||||
|
||||
static volatile int e_steps; //Extrusion steps to be executed by the stepper
|
||||
static int final_estep_rate; //Speed of extruder at cruising speed
|
||||
static int current_estep_rate; //The current speed of the extruder
|
||||
static int current_adv_steps; //The current pretension of filament expressed in steps
|
||||
|
||||
#define ADV_RATE(T, L) (e_steps ? (T) * (L) / abs(e_steps) : ADV_NEVER)
|
||||
#define _NEXT_ISR(T) nextMainISR = T
|
||||
|
||||
#else
|
||||
#define _NEXT_ISR(T) OCR1A = T
|
||||
#endif
|
||||
|
||||
//===========================================================================
|
||||
//=============================functions ============================
|
||||
//===========================================================================
|
||||
|
||||
#define CHECK_ENDSTOPS if(check_endstops)
|
||||
|
||||
#ifndef _NO_ASM
|
||||
|
||||
// intRes = intIn1 * intIn2 >> 16
|
||||
// uses:
|
||||
// r26 to store 0
|
||||
|
@ -169,6 +200,18 @@ asm volatile ( \
|
|||
"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
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1<<OCIE1A)
|
||||
|
@ -283,6 +326,7 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
|
|||
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
|
||||
|
@ -306,13 +350,6 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
|
|||
// Initializes the trapezoid generator from the current block. Called whenever a new
|
||||
// block begins.
|
||||
FORCE_INLINE void trapezoid_generator_reset() {
|
||||
#ifdef ADVANCE
|
||||
advance = current_block->initial_advance;
|
||||
final_advance = current_block->final_advance;
|
||||
// Do E steps + advance steps
|
||||
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
|
||||
old_advance = advance >>8;
|
||||
#endif
|
||||
deceleration_time = 0;
|
||||
// step_rate to timer interval
|
||||
OCR1A_nominal = calc_timer(current_block->nominal_rate);
|
||||
|
@ -320,30 +357,39 @@ FORCE_INLINE void trapezoid_generator_reset() {
|
|||
step_loops_nominal = step_loops;
|
||||
acc_step_rate = current_block->initial_rate;
|
||||
acceleration_time = calc_timer(acc_step_rate);
|
||||
OCR1A = acceleration_time;
|
||||
_NEXT_ISR(acceleration_time);
|
||||
|
||||
// SERIAL_ECHO_START;
|
||||
// SERIAL_ECHOPGM("advance :");
|
||||
// SERIAL_ECHO(current_block->advance/256.0);
|
||||
// SERIAL_ECHOPGM("advance rate :");
|
||||
// SERIAL_ECHO(current_block->advance_rate/256.0);
|
||||
// SERIAL_ECHOPGM("initial advance :");
|
||||
// SERIAL_ECHO(current_block->initial_advance/256.0);
|
||||
// SERIAL_ECHOPGM("final advance :");
|
||||
// SERIAL_ECHOLN(current_block->final_advance/256.0);
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
current_estep_rate = ((unsigned long)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
|
||||
final_estep_rate = (current_block->nominal_rate * current_block->abs_adv_steps_multiplier8) >> 17;
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
// "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)
|
||||
{
|
||||
ISR(TIMER1_COMPA_vect) {
|
||||
#ifdef LIN_ADVANCE
|
||||
advance_isr_scheduler();
|
||||
#else
|
||||
isr();
|
||||
#endif
|
||||
}
|
||||
|
||||
void isr() {
|
||||
//if (UVLO) uvlo();
|
||||
// If there is no current block, attempt to pop one from the buffer
|
||||
if (current_block == NULL) {
|
||||
// Anything in the buffer?
|
||||
current_block = plan_get_current_block();
|
||||
if (current_block != NULL) {
|
||||
// The busy flag is set by the plan_get_current_block() call.
|
||||
#ifdef PAT9125
|
||||
fsensor_counter = 0;
|
||||
fsensor_st_block_begin(current_block);
|
||||
#endif //PAT9125
|
||||
// The busy flag is set by the plan_get_current_block() call.
|
||||
// current_block->busy = true;
|
||||
trapezoid_generator_reset();
|
||||
counter_x = -(current_block->step_event_count >> 1);
|
||||
|
@ -355,20 +401,18 @@ ISR(TIMER1_COMPA_vect)
|
|||
#ifdef Z_LATE_ENABLE
|
||||
if(current_block->steps_z > 0) {
|
||||
enable_z();
|
||||
OCR1A = 2000; //1ms wait
|
||||
_NEXT_ISR(2000); //1ms wait
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// #ifdef ADVANCE
|
||||
// e_steps[current_block->active_extruder] = 0;
|
||||
// #endif
|
||||
}
|
||||
else {
|
||||
OCR1A=2000; // 1kHz.
|
||||
_NEXT_ISR(2000); // 1kHz.
|
||||
}
|
||||
}
|
||||
|
||||
LastStepMask = 0;
|
||||
|
||||
if (current_block != NULL) {
|
||||
// Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
|
||||
out_bits = current_block->direction_bits;
|
||||
|
@ -411,8 +455,19 @@ ISR(TIMER1_COMPA_vect)
|
|||
CHECK_ENDSTOPS
|
||||
{
|
||||
{
|
||||
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
||||
bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
|
||||
#if ( (defined(X_MIN_PIN) && (X_MIN_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_XMINLIMIT)
|
||||
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
// Stall guard homing turned on, now decide if software or hardware one
|
||||
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||
x_min_endstop = (READ(X_TMC2130_DIAG) != X_MIN_ENDSTOP_INVERTING);
|
||||
#else //TMC2130_SG_HOMING_SW_XY
|
||||
x_min_endstop = tmc2130_axis_stalled[X_AXIS];
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
#else
|
||||
// Normal homing
|
||||
x_min_endstop = (READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
|
||||
#endif
|
||||
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||
endstop_x_hit=true;
|
||||
|
@ -427,8 +482,19 @@ ISR(TIMER1_COMPA_vect)
|
|||
CHECK_ENDSTOPS
|
||||
{
|
||||
{
|
||||
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
||||
bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
|
||||
#if ( (defined(X_MAX_PIN) && (X_MAX_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_XMAXLIMIT)
|
||||
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
// Stall guard homing turned on, now decide if software or hardware one
|
||||
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||
x_max_endstop = (READ(X_TMC2130_DIAG) != X_MAX_ENDSTOP_INVERTING);
|
||||
#else //TMC2130_SG_HOMING_SW_XY
|
||||
x_max_endstop = tmc2130_axis_stalled[X_AXIS];
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
#else
|
||||
// Normal homing
|
||||
x_max_endstop = (READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
|
||||
#endif
|
||||
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||
endstop_x_hit=true;
|
||||
|
@ -447,8 +513,20 @@ ISR(TIMER1_COMPA_vect)
|
|||
#endif
|
||||
CHECK_ENDSTOPS
|
||||
{
|
||||
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
||||
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
|
||||
|
||||
#if ( (defined(Y_MIN_PIN) && (Y_MIN_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_YMINLIMIT)
|
||||
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
// Stall guard homing turned on, now decide if software or hardware one
|
||||
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||
y_min_endstop = (READ(Y_TMC2130_DIAG) != Y_MIN_ENDSTOP_INVERTING);
|
||||
#else //TMC2130_SG_HOMING_SW_XY
|
||||
y_min_endstop = tmc2130_axis_stalled[Y_AXIS];
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
#else
|
||||
// Normal homing
|
||||
y_min_endstop = (READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
|
||||
#endif
|
||||
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
|
||||
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
||||
endstop_y_hit=true;
|
||||
|
@ -461,8 +539,19 @@ ISR(TIMER1_COMPA_vect)
|
|||
else { // +direction
|
||||
CHECK_ENDSTOPS
|
||||
{
|
||||
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
||||
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
|
||||
#if ( (defined(Y_MAX_PIN) && (Y_MAX_PIN > -1)) || defined(TMC2130_SG_HOMING) ) && !defined(DEBUG_DISABLE_YMAXLIMIT)
|
||||
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
// Stall guard homing turned on, now decide if software or hardware one
|
||||
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||
y_max_endstop = (READ(Y_TMC2130_DIAG) != Y_MAX_ENDSTOP_INVERTING);
|
||||
#else //TMC2130_SG_HOMING_SW_XY
|
||||
y_max_endstop = tmc2130_axis_stalled[Y_AXIS];
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
#else
|
||||
// Normal homing
|
||||
y_max_endstop = (READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
|
||||
#endif
|
||||
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
|
||||
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
||||
endstop_y_hit=true;
|
||||
|
@ -483,8 +572,8 @@ ISR(TIMER1_COMPA_vect)
|
|||
count_direction[Z_AXIS]=-1;
|
||||
if(check_endstops && ! check_z_endstop)
|
||||
{
|
||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
||||
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
#if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
|
||||
z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_hit=true;
|
||||
|
@ -504,8 +593,12 @@ ISR(TIMER1_COMPA_vect)
|
|||
count_direction[Z_AXIS]=1;
|
||||
CHECK_ENDSTOPS
|
||||
{
|
||||
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
|
||||
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
|
||||
#if defined(Z_MAX_PIN) && (Z_MAX_PIN > -1) && !defined(DEBUG_DISABLE_ZMAXLIMIT)
|
||||
#ifndef TMC2130_SG_HOMING_SW_Z
|
||||
z_max_endstop = (READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
|
||||
#else //TMC2130_SG_HOMING_SW_Z
|
||||
z_max_endstop = tmc2130_axis_stalled[Z_AXIS];
|
||||
#endif //TMC2130_SG_HOMING_SW_Z
|
||||
if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_hit=true;
|
||||
|
@ -517,11 +610,11 @@ ISR(TIMER1_COMPA_vect)
|
|||
}
|
||||
|
||||
// Supporting stopping on a trigger of the Z-stop induction sensor, not only for the Z-minus movements.
|
||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
||||
#if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
|
||||
if(check_z_endstop) {
|
||||
// Check the Z min end-stop no matter what.
|
||||
// Good for searching for the center of an induction target.
|
||||
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
|
||||
if(z_min_endstop && old_z_min_endstop) {
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_z_hit=true;
|
||||
|
@ -531,48 +624,76 @@ ISR(TIMER1_COMPA_vect)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef ADVANCE
|
||||
if ((out_bits & (1<<E_AXIS)) != 0) { // -direction
|
||||
REV_E_DIR();
|
||||
count_direction[E_AXIS]=-1;
|
||||
}
|
||||
else { // +direction
|
||||
NORM_E_DIR();
|
||||
count_direction[E_AXIS]=1;
|
||||
}
|
||||
#endif //!ADVANCE
|
||||
if ((out_bits & (1 << E_AXIS)) != 0)
|
||||
{ // -direction
|
||||
//AKU
|
||||
#ifdef SNMM
|
||||
if (snmm_extruder == 0 || snmm_extruder == 2)
|
||||
{
|
||||
NORM_E_DIR();
|
||||
}
|
||||
else
|
||||
{
|
||||
REV_E_DIR();
|
||||
}
|
||||
#else
|
||||
REV_E_DIR();
|
||||
#endif // SNMM
|
||||
count_direction[E_AXIS] = -1;
|
||||
}
|
||||
else
|
||||
{ // +direction
|
||||
#ifdef SNMM
|
||||
if (snmm_extruder == 0 || snmm_extruder == 2)
|
||||
{
|
||||
REV_E_DIR();
|
||||
}
|
||||
else
|
||||
{
|
||||
NORM_E_DIR();
|
||||
}
|
||||
#else
|
||||
NORM_E_DIR();
|
||||
#endif // SNMM
|
||||
count_direction[E_AXIS] = 1;
|
||||
}
|
||||
|
||||
|
||||
|
||||
for(int8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
|
||||
for(uint8_t i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves)
|
||||
#ifndef AT90USB
|
||||
MSerial.checkRx(); // Check for serial chars.
|
||||
#endif
|
||||
|
||||
#ifdef ADVANCE
|
||||
counter_e += current_block->steps_e;
|
||||
if (counter_e > 0) {
|
||||
counter_e -= current_block->step_event_count;
|
||||
if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
|
||||
e_steps[current_block->active_extruder]--;
|
||||
#ifdef LIN_ADVANCE
|
||||
counter_e += current_block->steps_e;
|
||||
if (counter_e > 0) {
|
||||
counter_e -= current_block->step_event_count;
|
||||
count_position[E_AXIS] += count_direction[E_AXIS];
|
||||
((out_bits&(1<<E_AXIS))!=0) ? --e_steps : ++e_steps;
|
||||
}
|
||||
else {
|
||||
e_steps[current_block->active_extruder]++;
|
||||
}
|
||||
}
|
||||
#endif //ADVANCE
|
||||
|
||||
#endif
|
||||
|
||||
counter_x += current_block->steps_x;
|
||||
if (counter_x > 0) {
|
||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||
LastStepMask |= X_AXIS_MASK;
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
counter_x -= current_block->step_event_count;
|
||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
}
|
||||
|
||||
counter_y += current_block->steps_y;
|
||||
if (counter_y > 0) {
|
||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
LastStepMask |= Y_AXIS_MASK;
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Y2_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
|
@ -581,6 +702,9 @@ ISR(TIMER1_COMPA_vect)
|
|||
counter_y -= current_block->step_event_count;
|
||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Y2_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
|
@ -590,7 +714,7 @@ ISR(TIMER1_COMPA_vect)
|
|||
counter_z += current_block->steps_z;
|
||||
if (counter_z > 0) {
|
||||
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
|
||||
LastStepMask |= Z_AXIS_MASK;
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
#endif
|
||||
|
@ -604,23 +728,37 @@ ISR(TIMER1_COMPA_vect)
|
|||
#endif
|
||||
}
|
||||
|
||||
#ifndef ADVANCE
|
||||
#ifndef LIN_ADVANCE
|
||||
counter_e += current_block->steps_e;
|
||||
if (counter_e > 0) {
|
||||
WRITE_E_STEP(!INVERT_E_STEP_PIN);
|
||||
counter_e -= current_block->step_event_count;
|
||||
count_position[E_AXIS]+=count_direction[E_AXIS];
|
||||
WRITE_E_STEP(INVERT_E_STEP_PIN);
|
||||
#ifdef PAT9125
|
||||
fsensor_counter++;
|
||||
#endif //PAT9125
|
||||
}
|
||||
#endif //!ADVANCE
|
||||
#endif
|
||||
|
||||
step_events_completed += 1;
|
||||
if(step_events_completed >= current_block->step_event_count) break;
|
||||
}
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
const int delta_adv_steps = current_estep_rate - current_adv_steps;
|
||||
current_adv_steps += delta_adv_steps;
|
||||
e_steps += delta_adv_steps;
|
||||
}
|
||||
// If we have esteps to execute, fire the next advance_isr "now"
|
||||
if (e_steps) nextAdvanceISR = 0;
|
||||
#endif
|
||||
|
||||
// Calculare new timer value
|
||||
unsigned short timer;
|
||||
unsigned short step_rate;
|
||||
uint16_t step_rate;
|
||||
if (step_events_completed <= (unsigned long int)current_block->accelerate_until) {
|
||||
|
||||
// v = t * a -> acc_step_rate = acceleration_time * current_block->acceleration_rate
|
||||
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
|
||||
acc_step_rate += current_block->initial_rate;
|
||||
|
||||
|
@ -630,18 +768,15 @@ ISR(TIMER1_COMPA_vect)
|
|||
|
||||
// step_rate to timer interval
|
||||
timer = calc_timer(acc_step_rate);
|
||||
OCR1A = timer;
|
||||
_NEXT_ISR(timer);
|
||||
acceleration_time += timer;
|
||||
#ifdef ADVANCE
|
||||
for(int8_t i=0; i < step_loops; i++) {
|
||||
advance += advance_rate;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
current_estep_rate = ((uint32_t)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
|
||||
}
|
||||
//if(advance > current_block->advance) advance = current_block->advance;
|
||||
// Do E steps + advance steps
|
||||
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
|
||||
old_advance = advance >>8;
|
||||
|
||||
#endif // ADVANCE
|
||||
eISR_Rate = ADV_RATE(timer, step_loops);
|
||||
#endif
|
||||
}
|
||||
else if (step_events_completed > (unsigned long int)current_block->decelerate_after) {
|
||||
MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
|
||||
|
@ -659,91 +794,127 @@ ISR(TIMER1_COMPA_vect)
|
|||
|
||||
// step_rate to timer interval
|
||||
timer = calc_timer(step_rate);
|
||||
OCR1A = timer;
|
||||
_NEXT_ISR(timer);
|
||||
deceleration_time += timer;
|
||||
#ifdef ADVANCE
|
||||
for(int8_t i=0; i < step_loops; i++) {
|
||||
advance -= advance_rate;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead) {
|
||||
current_estep_rate = ((uint32_t)step_rate * current_block->abs_adv_steps_multiplier8) >> 17;
|
||||
}
|
||||
if(advance < final_advance) advance = final_advance;
|
||||
// Do E steps + advance steps
|
||||
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
|
||||
old_advance = advance >>8;
|
||||
#endif //ADVANCE
|
||||
eISR_Rate = ADV_RATE(timer, step_loops);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
OCR1A = OCR1A_nominal;
|
||||
#ifdef LIN_ADVANCE
|
||||
if (current_block->use_advance_lead)
|
||||
current_estep_rate = final_estep_rate;
|
||||
|
||||
eISR_Rate = ADV_RATE(OCR1A_nominal, step_loops_nominal);
|
||||
#endif
|
||||
|
||||
_NEXT_ISR(OCR1A_nominal);
|
||||
// ensure we're running at the correct step rate, even if we just came off an acceleration
|
||||
step_loops = step_loops_nominal;
|
||||
}
|
||||
|
||||
// If current block is finished, reset pointer
|
||||
if (step_events_completed >= current_block->step_event_count) {
|
||||
|
||||
#ifdef PAT9125
|
||||
fsensor_st_block_chunk(current_block, fsensor_counter);
|
||||
fsensor_counter = 0;
|
||||
#endif //PAT9125
|
||||
|
||||
current_block = NULL;
|
||||
plan_discard_current_block();
|
||||
}
|
||||
#ifdef PAT9125
|
||||
else if (fsensor_counter >= fsensor_chunk_len)
|
||||
{
|
||||
fsensor_st_block_chunk(current_block, fsensor_counter);
|
||||
fsensor_counter = 0;
|
||||
}
|
||||
#endif //PAT9125
|
||||
}
|
||||
#ifdef TMC2130
|
||||
tmc2130_st_isr(LastStepMask);
|
||||
#endif //TMC2130
|
||||
}
|
||||
|
||||
#ifdef ADVANCE
|
||||
unsigned char old_OCR0A;
|
||||
// Timer interrupt for E. e_steps is set in the main routine;
|
||||
// Timer 0 is shared with millies
|
||||
ISR(TIMER0_COMPA_vect)
|
||||
{
|
||||
old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz)
|
||||
OCR0A = old_OCR0A;
|
||||
// Set E direction (Depends on E direction + advance)
|
||||
for(unsigned char i=0; i<4;i++) {
|
||||
if (e_steps[0] != 0) {
|
||||
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
if (e_steps[0] < 0) {
|
||||
WRITE(E0_DIR_PIN, INVERT_E0_DIR);
|
||||
e_steps[0]++;
|
||||
#ifdef LIN_ADVANCE
|
||||
|
||||
// Timer interrupt for E. e_steps is set in the main routine.
|
||||
|
||||
void advance_isr() {
|
||||
if (e_steps) {
|
||||
bool dir =
|
||||
#ifdef SNMM
|
||||
((e_steps < 0) == (snmm_extruder & 1))
|
||||
#else
|
||||
(e_steps < 0)
|
||||
#endif
|
||||
? INVERT_E0_DIR : !INVERT_E0_DIR; //If we have SNMM, reverse every second extruder.
|
||||
WRITE(E0_DIR_PIN, dir);
|
||||
|
||||
for (uint8_t i = step_loops; e_steps && i--;) {
|
||||
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
}
|
||||
else if (e_steps[0] > 0) {
|
||||
WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
|
||||
e_steps[0]--;
|
||||
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
}
|
||||
}
|
||||
#if EXTRUDERS > 1
|
||||
if (e_steps[1] != 0) {
|
||||
WRITE(E1_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
if (e_steps[1] < 0) {
|
||||
WRITE(E1_DIR_PIN, INVERT_E1_DIR);
|
||||
e_steps[1]++;
|
||||
WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
}
|
||||
else if (e_steps[1] > 0) {
|
||||
WRITE(E1_DIR_PIN, !INVERT_E1_DIR);
|
||||
e_steps[1]--;
|
||||
WRITE(E1_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#if EXTRUDERS > 2
|
||||
if (e_steps[2] != 0) {
|
||||
WRITE(E2_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
if (e_steps[2] < 0) {
|
||||
WRITE(E2_DIR_PIN, INVERT_E2_DIR);
|
||||
e_steps[2]++;
|
||||
WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
}
|
||||
else if (e_steps[2] > 0) {
|
||||
WRITE(E2_DIR_PIN, !INVERT_E2_DIR);
|
||||
e_steps[2]--;
|
||||
WRITE(E2_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif // ADVANCE
|
||||
e_steps < 0 ? ++e_steps : --e_steps;
|
||||
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
#ifdef PAT9125
|
||||
fsensor_counter++;
|
||||
#endif //PAT9125
|
||||
|
||||
}
|
||||
}
|
||||
else {
|
||||
eISR_Rate = ADV_NEVER;
|
||||
}
|
||||
nextAdvanceISR = eISR_Rate;
|
||||
}
|
||||
|
||||
void advance_isr_scheduler() {
|
||||
// Run main stepping ISR if flagged
|
||||
if (!nextMainISR) isr();
|
||||
|
||||
// Run Advance stepping ISR if flagged
|
||||
if (!nextAdvanceISR) advance_isr();
|
||||
|
||||
// Is the next advance ISR scheduled before the next main ISR?
|
||||
if (nextAdvanceISR <= nextMainISR) {
|
||||
// Set up the next interrupt
|
||||
OCR1A = nextAdvanceISR;
|
||||
// New interval for the next main ISR
|
||||
if (nextMainISR) nextMainISR -= nextAdvanceISR;
|
||||
// Will call Stepper::advance_isr on the next interrupt
|
||||
nextAdvanceISR = 0;
|
||||
}
|
||||
else {
|
||||
// The next main ISR comes first
|
||||
OCR1A = nextMainISR;
|
||||
// New interval for the next advance ISR, if any
|
||||
if (nextAdvanceISR && nextAdvanceISR != ADV_NEVER)
|
||||
nextAdvanceISR -= nextMainISR;
|
||||
// Will call Stepper::isr on the next interrupt
|
||||
nextMainISR = 0;
|
||||
}
|
||||
|
||||
// Don't run the ISR faster than possible
|
||||
if (OCR1A < TCNT1 + 16) OCR1A = TCNT1 + 16;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
#endif // LIN_ADVANCE
|
||||
|
||||
void st_init()
|
||||
{
|
||||
#ifdef TMC2130
|
||||
tmc2130_init();
|
||||
#endif //TMC2130
|
||||
|
||||
digipot_init(); //Initialize Digipot Motor Current
|
||||
microstep_init(); //Initialize Microstepping Pins
|
||||
|
||||
|
@ -821,6 +992,18 @@ void st_init()
|
|||
|
||||
//endstops and pullups
|
||||
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
SET_INPUT(X_TMC2130_DIAG);
|
||||
WRITE(X_TMC2130_DIAG,HIGH);
|
||||
|
||||
SET_INPUT(Y_TMC2130_DIAG);
|
||||
WRITE(Y_TMC2130_DIAG,HIGH);
|
||||
|
||||
SET_INPUT(Z_TMC2130_DIAG);
|
||||
WRITE(Z_TMC2130_DIAG,HIGH);
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
||||
SET_INPUT(X_MIN_PIN);
|
||||
#ifdef ENDSTOPPULLUP_XMIN
|
||||
|
@ -865,9 +1048,13 @@ void st_init()
|
|||
|
||||
|
||||
//Initialize Step Pins
|
||||
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
|
||||
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
|
||||
SET_OUTPUT(X_STEP_PIN);
|
||||
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
SET_OUTPUT(DEBUG_XSTEP_DUP_PIN);
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
disable_x();
|
||||
#endif
|
||||
#if defined(X2_STEP_PIN) && (X2_STEP_PIN > -1)
|
||||
|
@ -878,6 +1065,10 @@ void st_init()
|
|||
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
|
||||
SET_OUTPUT(Y_STEP_PIN);
|
||||
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
SET_OUTPUT(DEBUG_YSTEP_DUP_PIN);
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
#if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_STEP_PIN) && (Y2_STEP_PIN > -1)
|
||||
SET_OUTPUT(Y2_STEP_PIN);
|
||||
WRITE(Y2_STEP_PIN,INVERT_Y_STEP_PIN);
|
||||
|
@ -930,17 +1121,11 @@ void st_init()
|
|||
TCNT1 = 0;
|
||||
ENABLE_STEPPER_DRIVER_INTERRUPT();
|
||||
|
||||
#ifdef ADVANCE
|
||||
#if defined(TCCR0A) && defined(WGM01)
|
||||
TCCR0A &= ~(1<<WGM01);
|
||||
TCCR0A &= ~(1<<WGM00);
|
||||
#endif
|
||||
e_steps[0] = 0;
|
||||
e_steps[1] = 0;
|
||||
e_steps[2] = 0;
|
||||
TIMSK0 |= (1<<OCIE0A);
|
||||
#endif //ADVANCE
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
e_steps = 0;
|
||||
current_adv_steps = 0;
|
||||
#endif
|
||||
|
||||
enable_endstops(true); // Start with endstops active. After homing they can be disabled
|
||||
sei();
|
||||
}
|
||||
|
@ -949,12 +1134,23 @@ void st_init()
|
|||
// Block until all buffered steps are executed
|
||||
void st_synchronize()
|
||||
{
|
||||
while( blocks_queued()) {
|
||||
manage_heater();
|
||||
// Vojtech: Don't disable motors inside the planner!
|
||||
manage_inactivity(true);
|
||||
lcd_update();
|
||||
}
|
||||
while(blocks_queued())
|
||||
{
|
||||
#ifdef TMC2130
|
||||
manage_heater();
|
||||
// Vojtech: Don't disable motors inside the planner!
|
||||
if (!tmc2130_update_sg())
|
||||
{
|
||||
manage_inactivity(true);
|
||||
lcd_update();
|
||||
}
|
||||
#else //TMC2130
|
||||
manage_heater();
|
||||
// Vojtech: Don't disable motors inside the planner!
|
||||
manage_inactivity(true);
|
||||
lcd_update();
|
||||
#endif //TMC2130
|
||||
}
|
||||
}
|
||||
|
||||
void st_set_position(const long &x, const long &y, const long &z, const long &e)
|
||||
|
@ -983,6 +1179,13 @@ long st_get_position(uint8_t axis)
|
|||
return count_pos;
|
||||
}
|
||||
|
||||
void st_get_position_xy(long &x, long &y)
|
||||
{
|
||||
CRITICAL_SECTION_START;
|
||||
x = count_position[X_AXIS];
|
||||
y = count_position[Y_AXIS];
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
|
||||
float st_get_position_mm(uint8_t axis)
|
||||
{
|
||||
|
@ -1029,10 +1232,17 @@ void babystep(const uint8_t axis,const bool direction)
|
|||
|
||||
//perform step
|
||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||
LastStepMask |= X_AXIS_MASK;
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
{
|
||||
float x=1./float(axis+1)/float(axis+2); //wait a tiny bit
|
||||
volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit
|
||||
}
|
||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
|
||||
//get old pin state back.
|
||||
WRITE(X_DIR_PIN,old_x_dir_pin);
|
||||
|
@ -1048,10 +1258,17 @@ void babystep(const uint8_t axis,const bool direction)
|
|||
|
||||
//perform step
|
||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
LastStepMask |= Y_AXIS_MASK;
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
{
|
||||
float x=1./float(axis+1)/float(axis+2); //wait a tiny bit
|
||||
volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit
|
||||
}
|
||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
|
||||
//get old pin state back.
|
||||
WRITE(Y_DIR_PIN,old_y_dir_pin);
|
||||
|
@ -1070,12 +1287,13 @@ void babystep(const uint8_t axis,const bool direction)
|
|||
#endif
|
||||
//perform step
|
||||
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
LastStepMask |= Z_AXIS_MASK;
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
#endif
|
||||
//wait a tiny bit
|
||||
{
|
||||
float x=1./float(axis+1); //absolutely useless
|
||||
volatile float x=1./float(axis+1); //absolutely useless
|
||||
}
|
||||
WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
|
@ -1139,7 +1357,7 @@ void digipot_init() //Initialize Digipot Motor Current
|
|||
pinMode(MOTOR_CURRENT_PWM_XY_PIN, OUTPUT);
|
||||
pinMode(MOTOR_CURRENT_PWM_Z_PIN, OUTPUT);
|
||||
pinMode(MOTOR_CURRENT_PWM_E_PIN, OUTPUT);
|
||||
if(SilentMode == 0){
|
||||
if((SilentMode == 0) || (farm_mode) ){
|
||||
|
||||
motor_current_setting[0] = motor_current_setting_loud[0];
|
||||
motor_current_setting[1] = motor_current_setting_loud[1];
|
||||
|
@ -1255,4 +1473,3 @@ void microstep_readings()
|
|||
SERIAL_PROTOCOLLN( digitalRead(E1_MS2_PIN));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -44,6 +44,16 @@ extern bool abort_on_endstop_hit;
|
|||
// Initialize and start the stepper motor subsystem
|
||||
void st_init();
|
||||
|
||||
// Interrupt Service Routines
|
||||
|
||||
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();
|
||||
|
||||
|
@ -54,6 +64,8 @@ void st_set_e_position(const long &e);
|
|||
// Get current position in steps
|
||||
long st_get_position(uint8_t axis);
|
||||
|
||||
// Get current x and y position in steps
|
||||
void st_get_position_xy(long &x, long &y);
|
||||
|
||||
// Get current position in mm
|
||||
float st_get_position_mm(uint8_t axis);
|
||||
|
@ -77,6 +89,10 @@ void checkStepperErrors(); //Print errors detected by the stepper
|
|||
void finishAndDisableSteppers();
|
||||
|
||||
extern block_t *current_block; // A pointer to the block currently being traced
|
||||
extern bool x_min_endstop;
|
||||
extern bool x_max_endstop;
|
||||
extern bool y_min_endstop;
|
||||
extern bool y_max_endstop;
|
||||
|
||||
void quickStop();
|
||||
|
||||
|
|
209
Firmware/swi2c.cpp
Normal file
209
Firmware/swi2c.cpp
Normal file
|
@ -0,0 +1,209 @@
|
|||
#include "uni_avr_rpi.h"
|
||||
|
||||
#ifdef SWI2C
|
||||
#include "swi2c.h"
|
||||
|
||||
#ifdef __AVR
|
||||
unsigned char swi2c_sda = 20; // SDA pin
|
||||
unsigned char swi2c_scl = 21; // SCL pin
|
||||
#endif //__AVR
|
||||
|
||||
#ifdef __RPI
|
||||
unsigned char swi2c_sda = 2; // SDA pin
|
||||
unsigned char swi2c_scl = 3; // SCL pin
|
||||
#endif //__RPI
|
||||
|
||||
unsigned char swi2c_cfg = 0xb1; // config
|
||||
// bit0..3 = clock delay factor = 1 << 1 = 2 [us]
|
||||
// bit4..7 = ack timeout factor = 1 << 11 = 2048 [cycles]
|
||||
|
||||
#define SWI2C_SDA swi2c_sda
|
||||
#define SWI2C_SCL swi2c_scl
|
||||
#define SWI2C_RMSK 0x01 //read mask (bit0 = 1)
|
||||
#define SWI2C_WMSK 0x00 //write mask (bit0 = 0)
|
||||
#define SWI2C_ASHF 0x01 //address shift (<< 1)
|
||||
#define SWI2C_DMSK 0x7f //device address mask
|
||||
|
||||
|
||||
void swi2c_init(unsigned char sda, unsigned char scl, unsigned char cfg)
|
||||
{
|
||||
swi2c_sda = sda;
|
||||
swi2c_scl = scl;
|
||||
swi2c_cfg = cfg;
|
||||
GPIO_OUT(SWI2C_SDA);
|
||||
GPIO_OUT(SWI2C_SCL);
|
||||
GPIO_SET(SWI2C_SDA);
|
||||
GPIO_SET(SWI2C_SCL);
|
||||
DELAY(1000);
|
||||
}
|
||||
|
||||
void swi2c_start(int delay)
|
||||
{
|
||||
GPIO_CLR(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
GPIO_CLR(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
}
|
||||
|
||||
void swi2c_stop(int delay)
|
||||
{
|
||||
GPIO_SET(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
GPIO_SET(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
}
|
||||
|
||||
void swi2c_ack(int delay)
|
||||
{
|
||||
GPIO_CLR(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
GPIO_SET(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
GPIO_CLR(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
}
|
||||
|
||||
int swi2c_wait_ack(int delay, int ackto)
|
||||
{
|
||||
GPIO_INP(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
// GPIO_SET(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
GPIO_SET(SWI2C_SCL);
|
||||
// DELAY(delay);
|
||||
int ack = 0;
|
||||
while (!(ack = !GPIO_GET(SWI2C_SDA)) && ackto--) DELAY(delay);
|
||||
GPIO_CLR(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
GPIO_OUT(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
GPIO_CLR(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
return ack;
|
||||
}
|
||||
|
||||
unsigned char swi2c_read(int delay)
|
||||
{
|
||||
GPIO_SET(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
GPIO_INP(SWI2C_SDA);
|
||||
unsigned char data = 0;
|
||||
int bit; for (bit = 7; bit >= 0; bit--)
|
||||
{
|
||||
GPIO_SET(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
data |= GPIO_GET(SWI2C_SDA) << bit;
|
||||
GPIO_CLR(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
}
|
||||
GPIO_OUT(SWI2C_SDA);
|
||||
return data;
|
||||
}
|
||||
|
||||
void swi2c_write(int delay, unsigned char data)
|
||||
{
|
||||
int bit; for (bit = 7; bit >= 0; bit--)
|
||||
{
|
||||
if (data & (1 << bit)) GPIO_SET(SWI2C_SDA);
|
||||
else GPIO_CLR(SWI2C_SDA);
|
||||
DELAY(delay);
|
||||
GPIO_SET(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
GPIO_CLR(SWI2C_SCL);
|
||||
DELAY(delay);
|
||||
}
|
||||
}
|
||||
|
||||
int swi2c_check(unsigned char dev_addr)
|
||||
{
|
||||
int delay = 1 << (swi2c_cfg & 0xf);
|
||||
int tmout = 1 << (swi2c_cfg >> 4);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, (dev_addr & SWI2C_DMSK) << SWI2C_ASHF);
|
||||
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||
swi2c_stop(delay);
|
||||
return 1;
|
||||
}
|
||||
|
||||
#ifdef SWI2C_A8 //8bit address
|
||||
|
||||
int swi2c_readByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte)
|
||||
{
|
||||
int delay = 1 << (swi2c_cfg & 0xf);
|
||||
int tmout = 1 << (swi2c_cfg >> 4);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||
swi2c_write(delay, addr & 0xff);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_stop(delay);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
unsigned char byte = swi2c_read(delay);
|
||||
swi2c_stop(delay);
|
||||
if (pbyte) *pbyte = byte;
|
||||
return 1;
|
||||
}
|
||||
|
||||
int swi2c_writeByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte)
|
||||
{
|
||||
int delay = 1 << (swi2c_cfg & 0xf);
|
||||
int tmout = 1 << (swi2c_cfg >> 4);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||
swi2c_write(delay, addr & 0xff);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_write(delay, *pbyte);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_stop(delay);
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif //SWI2C_A8
|
||||
|
||||
#ifdef SWI2C_A16 //16bit address
|
||||
|
||||
int swi2c_readByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte)
|
||||
{
|
||||
int delay = 1 << (swi2c_cfg & 0xf);
|
||||
int tmout = 1 << (swi2c_cfg >> 4);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||
swi2c_write(delay, addr >> 8);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_write(delay, addr & 0xff);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_stop(delay);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
unsigned char byte = swi2c_read(delay);
|
||||
swi2c_stop(delay);
|
||||
if (pbyte) *pbyte = byte;
|
||||
return 1;
|
||||
}
|
||||
|
||||
int swi2c_writeByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte)
|
||||
{
|
||||
int delay = 1 << (swi2c_cfg & 0xf);
|
||||
int tmout = 1 << (swi2c_cfg >> 4);
|
||||
swi2c_start(delay);
|
||||
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
|
||||
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
|
||||
swi2c_write(delay, addr >> 8);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_write(delay, addr & 0xff);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_write(delay, *pbyte);
|
||||
if (!swi2c_wait_ack(delay, tmout)) return 0;
|
||||
swi2c_stop(delay);
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif //SWI2C_A16
|
||||
|
||||
|
||||
#endif //SWI2C
|
22
Firmware/swi2c.h
Normal file
22
Firmware/swi2c.h
Normal file
|
@ -0,0 +1,22 @@
|
|||
#ifndef SWI2C_H
|
||||
#define SWI2C_H
|
||||
|
||||
//initialize
|
||||
extern void swi2c_init(unsigned char sda, unsigned char scl, unsigned char cfg);
|
||||
|
||||
//check device address acknowledge
|
||||
extern int swi2c_check(unsigned char dev_addr);
|
||||
|
||||
//read write functions - 8bit address (most i2c chips)
|
||||
#ifdef SWI2C_A8
|
||||
extern int swi2c_readByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte);
|
||||
extern int swi2c_writeByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte);
|
||||
#endif //SWI2C_A8
|
||||
|
||||
//read write functions - 16bit address (e.g. serial eeprom AT24C256)
|
||||
#ifdef SWI2C_A16
|
||||
extern int swi2c_readByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte);
|
||||
extern int swi2c_writeByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte);
|
||||
#endif //SWI2C_A16
|
||||
|
||||
#endif //SWI2C_H
|
93
Firmware/swspi.cpp
Executable file
93
Firmware/swspi.cpp
Executable file
|
@ -0,0 +1,93 @@
|
|||
#include "uni_avr_rpi.h"
|
||||
|
||||
#ifdef __SWSPI
|
||||
#include "swspi.h"
|
||||
|
||||
#ifdef __RPI
|
||||
//#define swspi_miso 9
|
||||
#define swspi_miso 10
|
||||
#define swspi_mosi 10
|
||||
#define swspi_sck 11
|
||||
#define SWSPI_CS 7
|
||||
#endif //__RPI
|
||||
|
||||
|
||||
#define SWSPI_DEL 0x0f //delay mask (0-3. bit, delay = 1 << DEL [us])
|
||||
#define SWSPI_POL 0x10 //polarity mask (4. bit, 1=inverted)
|
||||
#define SWSPI_PHA 0x20 //phase mask (5. bit)
|
||||
#define SWSPI_DOR 0x40 //data order mask (6. bit, 0=MSB first, 1=LSB first)
|
||||
|
||||
#define SWSPI_SCK_UP if (swspi_cfg & SWSPI_POL) GPIO_CLR(swspi_sck); else GPIO_SET(swspi_sck);
|
||||
#define SWSPI_SCK_DN if (swspi_cfg & SWSPI_POL) GPIO_SET(swspi_sck); else GPIO_CLR(swspi_sck);
|
||||
|
||||
unsigned char swspi_miso = 0;
|
||||
unsigned char swspi_mosi = 0;
|
||||
unsigned char swspi_sck = 0;
|
||||
unsigned char swspi_cfg = 0;
|
||||
|
||||
void swspi_init(unsigned char miso, unsigned char mosi, unsigned char sck, unsigned char cfg)
|
||||
{
|
||||
swspi_miso = miso;
|
||||
swspi_mosi = mosi;
|
||||
swspi_sck = sck;
|
||||
swspi_cfg = cfg;
|
||||
GPIO_INP(swspi_miso);
|
||||
GPIO_OUT(swspi_mosi);
|
||||
GPIO_OUT(swspi_sck);
|
||||
GPIO_CLR(swspi_mosi);
|
||||
SWSPI_SCK_DN;
|
||||
}
|
||||
|
||||
void swspi_tx(unsigned char tx)
|
||||
{
|
||||
int delay = 1 << (swspi_cfg & SWSPI_DEL));
|
||||
if (swspi_miso == swspi_mosi) GPIO_OUT(swspi_mosi);
|
||||
unsigned char i = 0; for (; i < 8; i++)
|
||||
{
|
||||
if (tx & 0x80) GPIO_SET(swspi_mosi);
|
||||
else GPIO_CLR(swspi_mosi);
|
||||
DELAY(delay);
|
||||
SWSPI_SCK_UP;
|
||||
DELAY(delay);
|
||||
SWSPI_SCK_DN;
|
||||
tx <<= 1;
|
||||
}
|
||||
}
|
||||
|
||||
unsigned char swspi_rx()
|
||||
{
|
||||
int delay = 1 << (swspi_cfg & SWSPI_DEL));
|
||||
if (swspi_miso == swspi_mosi) GPIO_OUT(swspi_mosi);
|
||||
unsigned char rx = 0;
|
||||
unsigned char i = 0; for (; i < 8; i++)
|
||||
{
|
||||
rx <<= 1;
|
||||
DELAY(delay);
|
||||
SWSPI_SCK_UP;
|
||||
DELAY(delay);
|
||||
rx |= GPIO_GET(swspi_miso)?1:0;
|
||||
SWSPI_SCK_DN;
|
||||
}
|
||||
return rx;
|
||||
}
|
||||
|
||||
unsigned char swspi_txrx(unsigned char tx)
|
||||
{
|
||||
int delay = 1 << (swspi_cfg & SWSPI_DEL));
|
||||
unsigned char rx = 0;
|
||||
unsigned char i = 0; for (; i < 8; i++)
|
||||
{
|
||||
rx <<= 1;
|
||||
if (tx & 0x80) GPIO_SET(swspi_mosi);
|
||||
else GPIO_CLR(swspi_mosi);
|
||||
DELAY(delay);
|
||||
SWSPI_SCK_UP;
|
||||
DELAY(delay);
|
||||
rx |= GPIO_GET(swspi_miso)?1:0;
|
||||
SWSPI_SCK_DN;
|
||||
tx <<= 1;
|
||||
}
|
||||
return rx;
|
||||
}
|
||||
|
||||
#endif //__SWSPI
|
14
Firmware/swspi.h
Executable file
14
Firmware/swspi.h
Executable file
|
@ -0,0 +1,14 @@
|
|||
// Software SPI
|
||||
#ifndef SWSPI_H
|
||||
#define SWSPI_H
|
||||
|
||||
//initialize gpio
|
||||
extern void swspi_init(unsigned char miso, unsigned char mosi, unsigned char sck, unsigned char cfg);
|
||||
//transmit and receive (full duplex mode)
|
||||
extern unsigned char swspi_txrx(unsigned char tx);
|
||||
//transmit (half dublex mode, miso == mosi)
|
||||
extern void swspi_tx(unsigned char tx);
|
||||
//receive (half dublex mode, miso == mosi)
|
||||
extern unsigned char swspi_rx();
|
||||
|
||||
#endif //SWSPI_H
|
File diff suppressed because it is too large
Load diff
|
@ -1,209 +1,228 @@
|
|||
/*
|
||||
temperature.h - temperature controller
|
||||
Part of Marlin
|
||||
|
||||
Copyright (c) 2011 Erik van der Zalm
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef temperature_h
|
||||
#define temperature_h
|
||||
|
||||
#include "Marlin.h"
|
||||
#include "planner.h"
|
||||
#ifdef PID_ADD_EXTRUSION_RATE
|
||||
#include "stepper.h"
|
||||
#endif
|
||||
|
||||
// public functions
|
||||
void tp_init(); //initialize the heating
|
||||
void manage_heater(); //it is critical that this is called periodically.
|
||||
|
||||
#ifdef FILAMENT_SENSOR
|
||||
// For converting raw Filament Width to milimeters
|
||||
float analog2widthFil();
|
||||
|
||||
// For converting raw Filament Width to an extrusion ratio
|
||||
int widthFil_to_size_ratio();
|
||||
#endif
|
||||
|
||||
// low level conversion routines
|
||||
// do not use these routines and variables outside of temperature.cpp
|
||||
extern int target_temperature[EXTRUDERS];
|
||||
extern float current_temperature[EXTRUDERS];
|
||||
#ifdef SHOW_TEMP_ADC_VALUES
|
||||
extern int current_temperature_raw[EXTRUDERS];
|
||||
extern int current_temperature_bed_raw;
|
||||
#endif
|
||||
extern int target_temperature_bed;
|
||||
extern float current_temperature_bed;
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
extern float redundant_temperature;
|
||||
#endif
|
||||
|
||||
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
|
||||
extern unsigned char soft_pwm_bed;
|
||||
#endif
|
||||
|
||||
#ifdef PIDTEMP
|
||||
extern float Kp,Ki,Kd,Kc;
|
||||
float scalePID_i(float i);
|
||||
float scalePID_d(float d);
|
||||
float unscalePID_i(float i);
|
||||
float unscalePID_d(float d);
|
||||
|
||||
#endif
|
||||
#ifdef PIDTEMPBED
|
||||
extern float bedKp,bedKi,bedKd;
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef BABYSTEPPING
|
||||
extern volatile int babystepsTodo[3];
|
||||
#endif
|
||||
|
||||
inline void babystepsTodoZadd(int n)
|
||||
{
|
||||
if (n != 0) {
|
||||
CRITICAL_SECTION_START
|
||||
babystepsTodo[Z_AXIS] += n;
|
||||
CRITICAL_SECTION_END
|
||||
}
|
||||
}
|
||||
|
||||
inline void babystepsTodoZsubtract(int n)
|
||||
{
|
||||
if (n != 0) {
|
||||
CRITICAL_SECTION_START
|
||||
babystepsTodo[Z_AXIS] -= n;
|
||||
CRITICAL_SECTION_END
|
||||
}
|
||||
}
|
||||
|
||||
//high level conversion routines, for use outside of temperature.cpp
|
||||
//inline so that there is no performance decrease.
|
||||
//deg=degreeCelsius
|
||||
|
||||
FORCE_INLINE float degHotend(uint8_t extruder) {
|
||||
return current_temperature[extruder];
|
||||
};
|
||||
|
||||
#ifdef SHOW_TEMP_ADC_VALUES
|
||||
FORCE_INLINE float rawHotendTemp(uint8_t extruder) {
|
||||
return current_temperature_raw[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE float rawBedTemp() {
|
||||
return current_temperature_bed_raw;
|
||||
};
|
||||
#endif
|
||||
|
||||
FORCE_INLINE float degBed() {
|
||||
return current_temperature_bed;
|
||||
};
|
||||
|
||||
FORCE_INLINE float degTargetHotend(uint8_t extruder) {
|
||||
return target_temperature[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE float degTargetBed() {
|
||||
return target_temperature_bed;
|
||||
};
|
||||
|
||||
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
|
||||
target_temperature[extruder] = celsius;
|
||||
};
|
||||
|
||||
FORCE_INLINE void setTargetBed(const float &celsius) {
|
||||
target_temperature_bed = celsius;
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
|
||||
return target_temperature[extruder] > current_temperature[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isHeatingBed() {
|
||||
return target_temperature_bed > current_temperature_bed;
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
|
||||
return target_temperature[extruder] < current_temperature[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isCoolingBed() {
|
||||
return target_temperature_bed < current_temperature_bed;
|
||||
};
|
||||
|
||||
#define degHotend0() degHotend(0)
|
||||
#define degTargetHotend0() degTargetHotend(0)
|
||||
#define setTargetHotend0(_celsius) setTargetHotend((_celsius), 0)
|
||||
#define isHeatingHotend0() isHeatingHotend(0)
|
||||
#define isCoolingHotend0() isCoolingHotend(0)
|
||||
#if EXTRUDERS > 1
|
||||
#define degHotend1() degHotend(1)
|
||||
#define degTargetHotend1() degTargetHotend(1)
|
||||
#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
|
||||
#define isHeatingHotend1() isHeatingHotend(1)
|
||||
#define isCoolingHotend1() isCoolingHotend(1)
|
||||
#else
|
||||
#define setTargetHotend1(_celsius) do{}while(0)
|
||||
#endif
|
||||
#if EXTRUDERS > 2
|
||||
#define degHotend2() degHotend(2)
|
||||
#define degTargetHotend2() degTargetHotend(2)
|
||||
#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
|
||||
#define isHeatingHotend2() isHeatingHotend(2)
|
||||
#define isCoolingHotend2() isCoolingHotend(2)
|
||||
#else
|
||||
#define setTargetHotend2(_celsius) do{}while(0)
|
||||
#endif
|
||||
#if EXTRUDERS > 3
|
||||
#error Invalid number of extruders
|
||||
#endif
|
||||
|
||||
#if (defined (TEMP_RUNAWAY_BED_HYSTERESIS) && TEMP_RUNAWAY_BED_TIMEOUT > 0) || (defined (TEMP_RUNAWAY_EXTRUDER_HYSTERESIS) && TEMP_RUNAWAY_EXTRUDER_TIMEOUT > 0)
|
||||
static float temp_runaway_status[4];
|
||||
static float temp_runaway_target[4];
|
||||
static float temp_runaway_timer[4];
|
||||
static int temp_runaway_error_counter[4];
|
||||
|
||||
void temp_runaway_check(int _heater_id, float _target_temperature, float _current_temperature, float _output, bool _isbed);
|
||||
void temp_runaway_stop();
|
||||
#endif
|
||||
|
||||
int getHeaterPower(int heater);
|
||||
void disable_heater();
|
||||
void setWatch();
|
||||
void updatePID();
|
||||
|
||||
|
||||
FORCE_INLINE void autotempShutdown(){
|
||||
#ifdef AUTOTEMP
|
||||
if(autotemp_enabled)
|
||||
{
|
||||
autotemp_enabled=false;
|
||||
if(degTargetHotend(active_extruder)>autotemp_min)
|
||||
setTargetHotend(0,active_extruder);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void PID_autotune(float temp, int extruder, int ncycles);
|
||||
|
||||
void setExtruderAutoFanState(int pin, bool state);
|
||||
void checkExtruderAutoFans();
|
||||
|
||||
#endif
|
||||
|
||||
/*
|
||||
temperature.h - temperature controller
|
||||
Part of Marlin
|
||||
|
||||
Copyright (c) 2011 Erik van der Zalm
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef temperature_h
|
||||
#define temperature_h
|
||||
|
||||
#include "Marlin.h"
|
||||
#include "planner.h"
|
||||
#ifdef PID_ADD_EXTRUSION_RATE
|
||||
#include "stepper.h"
|
||||
#endif
|
||||
|
||||
// public functions
|
||||
void tp_init(); //initialize the heating
|
||||
void manage_heater(); //it is critical that this is called periodically.
|
||||
|
||||
#ifdef FILAMENT_SENSOR
|
||||
// For converting raw Filament Width to milimeters
|
||||
float analog2widthFil();
|
||||
|
||||
// For converting raw Filament Width to an extrusion ratio
|
||||
int widthFil_to_size_ratio();
|
||||
#endif
|
||||
|
||||
// low level conversion routines
|
||||
// do not use these routines and variables outside of temperature.cpp
|
||||
extern int target_temperature[EXTRUDERS];
|
||||
extern float current_temperature[EXTRUDERS];
|
||||
#ifdef SHOW_TEMP_ADC_VALUES
|
||||
extern int current_temperature_raw[EXTRUDERS];
|
||||
extern int current_temperature_bed_raw;
|
||||
#endif
|
||||
extern int target_temperature_bed;
|
||||
extern float current_temperature_bed;
|
||||
|
||||
#ifdef PINDA_THERMISTOR
|
||||
//extern int current_temperature_raw_pinda;
|
||||
extern float current_temperature_pinda;
|
||||
#endif
|
||||
|
||||
#ifdef AMBIENT_THERMISTOR
|
||||
//extern int current_temperature_raw_ambient;
|
||||
extern float current_temperature_ambient;
|
||||
#endif
|
||||
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
extern float redundant_temperature;
|
||||
#endif
|
||||
|
||||
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
|
||||
extern unsigned char soft_pwm_bed;
|
||||
#endif
|
||||
|
||||
#ifdef PIDTEMP
|
||||
extern int pid_cycle, pid_number_of_cycles;
|
||||
extern float Kp,Ki,Kd,Kc,_Kp,_Ki,_Kd;
|
||||
extern bool pid_tuning_finished;
|
||||
float scalePID_i(float i);
|
||||
float scalePID_d(float d);
|
||||
float unscalePID_i(float i);
|
||||
float unscalePID_d(float d);
|
||||
|
||||
#endif
|
||||
#ifdef PIDTEMPBED
|
||||
extern float bedKp,bedKi,bedKd;
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef BABYSTEPPING
|
||||
extern volatile int babystepsTodo[3];
|
||||
#endif
|
||||
|
||||
inline void babystepsTodoZadd(int n)
|
||||
{
|
||||
if (n != 0) {
|
||||
CRITICAL_SECTION_START
|
||||
babystepsTodo[Z_AXIS] += n;
|
||||
CRITICAL_SECTION_END
|
||||
}
|
||||
}
|
||||
|
||||
inline void babystepsTodoZsubtract(int n)
|
||||
{
|
||||
if (n != 0) {
|
||||
CRITICAL_SECTION_START
|
||||
babystepsTodo[Z_AXIS] -= n;
|
||||
CRITICAL_SECTION_END
|
||||
}
|
||||
}
|
||||
|
||||
//high level conversion routines, for use outside of temperature.cpp
|
||||
//inline so that there is no performance decrease.
|
||||
//deg=degreeCelsius
|
||||
|
||||
FORCE_INLINE float degHotend(uint8_t extruder) {
|
||||
return current_temperature[extruder];
|
||||
};
|
||||
|
||||
#ifdef SHOW_TEMP_ADC_VALUES
|
||||
FORCE_INLINE float rawHotendTemp(uint8_t extruder) {
|
||||
return current_temperature_raw[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE float rawBedTemp() {
|
||||
return current_temperature_bed_raw;
|
||||
};
|
||||
#endif
|
||||
|
||||
FORCE_INLINE float degBed() {
|
||||
return current_temperature_bed;
|
||||
};
|
||||
|
||||
FORCE_INLINE float degTargetHotend(uint8_t extruder) {
|
||||
return target_temperature[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE float degTargetBed() {
|
||||
return target_temperature_bed;
|
||||
};
|
||||
|
||||
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
|
||||
target_temperature[extruder] = celsius;
|
||||
};
|
||||
|
||||
FORCE_INLINE void setTargetBed(const float &celsius) {
|
||||
target_temperature_bed = celsius;
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
|
||||
return target_temperature[extruder] > current_temperature[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isHeatingBed() {
|
||||
return target_temperature_bed > current_temperature_bed;
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
|
||||
return target_temperature[extruder] < current_temperature[extruder];
|
||||
};
|
||||
|
||||
FORCE_INLINE bool isCoolingBed() {
|
||||
return target_temperature_bed < current_temperature_bed;
|
||||
};
|
||||
|
||||
#define degHotend0() degHotend(0)
|
||||
#define degTargetHotend0() degTargetHotend(0)
|
||||
#define setTargetHotend0(_celsius) setTargetHotend((_celsius), 0)
|
||||
#define isHeatingHotend0() isHeatingHotend(0)
|
||||
#define isCoolingHotend0() isCoolingHotend(0)
|
||||
#if EXTRUDERS > 1
|
||||
#define degHotend1() degHotend(1)
|
||||
#define degTargetHotend1() degTargetHotend(1)
|
||||
#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
|
||||
#define isHeatingHotend1() isHeatingHotend(1)
|
||||
#define isCoolingHotend1() isCoolingHotend(1)
|
||||
#else
|
||||
#define setTargetHotend1(_celsius) do{}while(0)
|
||||
#endif
|
||||
#if EXTRUDERS > 2
|
||||
#define degHotend2() degHotend(2)
|
||||
#define degTargetHotend2() degTargetHotend(2)
|
||||
#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
|
||||
#define isHeatingHotend2() isHeatingHotend(2)
|
||||
#define isCoolingHotend2() isCoolingHotend(2)
|
||||
#else
|
||||
#define setTargetHotend2(_celsius) do{}while(0)
|
||||
#endif
|
||||
#if EXTRUDERS > 3
|
||||
#error Invalid number of extruders
|
||||
#endif
|
||||
|
||||
#if (defined (TEMP_RUNAWAY_BED_HYSTERESIS) && TEMP_RUNAWAY_BED_TIMEOUT > 0) || (defined (TEMP_RUNAWAY_EXTRUDER_HYSTERESIS) && TEMP_RUNAWAY_EXTRUDER_TIMEOUT > 0)
|
||||
static float temp_runaway_status[4];
|
||||
static float temp_runaway_target[4];
|
||||
static float temp_runaway_timer[4];
|
||||
static int temp_runaway_error_counter[4];
|
||||
|
||||
void temp_runaway_check(int _heater_id, float _target_temperature, float _current_temperature, float _output, bool _isbed);
|
||||
void temp_runaway_stop(bool isPreheat, bool isBed);
|
||||
#endif
|
||||
|
||||
int getHeaterPower(int heater);
|
||||
void disable_heater();
|
||||
void setWatch();
|
||||
void updatePID();
|
||||
|
||||
|
||||
FORCE_INLINE void autotempShutdown(){
|
||||
#ifdef AUTOTEMP
|
||||
if(autotemp_enabled)
|
||||
{
|
||||
autotemp_enabled=false;
|
||||
if(degTargetHotend(active_extruder)>autotemp_min)
|
||||
setTargetHotend(0,active_extruder);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void PID_autotune(float temp, int extruder, int ncycles);
|
||||
|
||||
void setExtruderAutoFanState(int pin, bool state);
|
||||
void checkExtruderAutoFans();
|
||||
|
||||
void countFanSpeed();
|
||||
void checkFanSpeed();
|
||||
void fanSpeedError(unsigned char _fan);
|
||||
|
||||
void check_fans();
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -1033,7 +1033,9 @@ const short temptable_12[][2] PROGMEM = {
|
|||
|
||||
#define PtA 3.9083E-3
|
||||
#define PtB -5.775E-7
|
||||
#define PtC -4.183E-12
|
||||
#define PtRt(T,R0) ((R0)*(1.0+(PtA)*(T)+(PtB)*(T)*(T)))
|
||||
#define PtRtNew(T,R0) ((R0)*(1.0+(PtA)*(T)+(PtB)*(T)*(T) + (T-100)*PtC*(T)*(T)*(T)))
|
||||
#define PtAdVal(T,R0,Rup) (short)(1024/(Rup/PtRt(T,R0)+1))
|
||||
#define PtLine(T,R0,Rup) { PtAdVal(T,R0,Rup)*OVERSAMPLENR, T },
|
||||
|
||||
|
@ -1061,6 +1063,124 @@ const short temptable_147[][2] PROGMEM = {
|
|||
PtLine(300,100,4700)
|
||||
};
|
||||
#endif
|
||||
// E3D Pt100 with 4k7 MiniRambo pullup, no Amp on the MiniRambo v1.3a
|
||||
#if (THERMISTORHEATER_0 == 148) || (THERMISTORHEATER_1 == 148) || (THERMISTORHEATER_2 == 148) || (THERMISTORBED == 148)
|
||||
const short temptable_148[][2] PROGMEM = {
|
||||
// These values have been calculated and tested over many days. See https://docs.google.com/spreadsheets/d/1MJXa6feEe0mGVCT2TrBwLxVOMoLDkJlvfQ4JXhAdV_E
|
||||
// Values that are missing from the 5C gap are missing due to resolution limits.
|
||||
{19.00000 * OVERSAMPLENR, 0},
|
||||
{19.25000 * OVERSAMPLENR, 5},
|
||||
{19.50000 * OVERSAMPLENR, 10},
|
||||
{19.87500 * OVERSAMPLENR, 15},
|
||||
{20.25000 * OVERSAMPLENR, 20},
|
||||
{21.00000 * OVERSAMPLENR, 25},
|
||||
{21.75000 * OVERSAMPLENR, 35},
|
||||
{22.00000 * OVERSAMPLENR, 40},
|
||||
{23.00000 * OVERSAMPLENR, 50}, // 55C is more commonly used.
|
||||
{23.75000 * OVERSAMPLENR, 60},
|
||||
{24.00000 * OVERSAMPLENR, 65},
|
||||
{24.06250 * OVERSAMPLENR, 70},
|
||||
{25.00000 * OVERSAMPLENR, 75},
|
||||
{25.50000 * OVERSAMPLENR, 85},
|
||||
{26.00000 * OVERSAMPLENR, 90},
|
||||
{26.93750 * OVERSAMPLENR,100},
|
||||
{27.00000 * OVERSAMPLENR,105},
|
||||
{27.37500 * OVERSAMPLENR,110},
|
||||
{28.00000 * OVERSAMPLENR,115},
|
||||
{29.00000 * OVERSAMPLENR,125},
|
||||
{29.25000 * OVERSAMPLENR,135},
|
||||
{30.00000 * OVERSAMPLENR,140},
|
||||
{35.50000 * OVERSAMPLENR,150},
|
||||
{31.00000 * OVERSAMPLENR,155},
|
||||
{32.00000 * OVERSAMPLENR,165},
|
||||
{32.18750 * OVERSAMPLENR,175},
|
||||
{33.00000 * OVERSAMPLENR,180},
|
||||
{33.62500 * OVERSAMPLENR,190},
|
||||
{34.00000 * OVERSAMPLENR,195},
|
||||
{35.00000 * OVERSAMPLENR,205},
|
||||
{35.50000 * OVERSAMPLENR,215},
|
||||
{36.00000 * OVERSAMPLENR,220},
|
||||
{36.75000 * OVERSAMPLENR,230},
|
||||
{37.00000 * OVERSAMPLENR,235},
|
||||
{37.75000 * OVERSAMPLENR,245},
|
||||
{38.00000 * OVERSAMPLENR,250},
|
||||
{38.12500 * OVERSAMPLENR,255},
|
||||
{39.00000 * OVERSAMPLENR,260},
|
||||
{40.00000 * OVERSAMPLENR,275},
|
||||
{40.25000 * OVERSAMPLENR,285},
|
||||
{41.00000 * OVERSAMPLENR,290},
|
||||
{41.25000 * OVERSAMPLENR,300},
|
||||
{42.00000 * OVERSAMPLENR,305},
|
||||
{43.00000 * OVERSAMPLENR,315},
|
||||
{43.25000 * OVERSAMPLENR,325},
|
||||
{44.00000 * OVERSAMPLENR,330},
|
||||
{44.18750 * OVERSAMPLENR,340},
|
||||
{45.00000 * OVERSAMPLENR,345},
|
||||
{45.25000 * OVERSAMPLENR,355},
|
||||
{46.00000 * OVERSAMPLENR,360},
|
||||
{46.62500 * OVERSAMPLENR,370},
|
||||
{47.00000 * OVERSAMPLENR,375},
|
||||
{47.25000 * OVERSAMPLENR,385},
|
||||
{48.00000 * OVERSAMPLENR,390},
|
||||
{48.75000 * OVERSAMPLENR,400},
|
||||
{49.00000 * OVERSAMPLENR,405},
|
||||
};
|
||||
#endif
|
||||
#if (THERMISTORHEATER_0 == 247) || (THERMISTORHEATER_1 == 247) || (THERMISTORHEATER_2 == 247) || (THERMISTORBED == 247) // Pt100 with 4k7 MiniRambo pullup & PT100 Amplifier
|
||||
const short temptable_247[][2] PROGMEM = {
|
||||
// Calculated from Bob-the-Kuhn's PT100 calculator listed in https://github.com/MarlinFirmware/Marlin/issues/5543
|
||||
// and the table provided by E3D at http://wiki.e3d-online.com/wiki/E3D_PT100_Amplifier_Documentation#Output_Characteristics.
|
||||
{ 0 * OVERSAMPLENR, 0},
|
||||
{241 * OVERSAMPLENR, 1},
|
||||
{249 * OVERSAMPLENR, 10},
|
||||
{259 * OVERSAMPLENR, 20},
|
||||
{267 * OVERSAMPLENR, 30},
|
||||
{275 * OVERSAMPLENR, 40},
|
||||
{283 * OVERSAMPLENR, 50},
|
||||
{291 * OVERSAMPLENR, 60},
|
||||
{299 * OVERSAMPLENR, 70},
|
||||
{307 * OVERSAMPLENR, 80},
|
||||
{315 * OVERSAMPLENR, 90},
|
||||
{323 * OVERSAMPLENR, 100},
|
||||
{331 * OVERSAMPLENR, 110},
|
||||
{340 * OVERSAMPLENR, 120},
|
||||
{348 * OVERSAMPLENR, 130},
|
||||
{354 * OVERSAMPLENR, 140},
|
||||
{362 * OVERSAMPLENR, 150},
|
||||
{370 * OVERSAMPLENR, 160},
|
||||
{378 * OVERSAMPLENR, 170},
|
||||
{386 * OVERSAMPLENR, 180},
|
||||
{394 * OVERSAMPLENR, 190},
|
||||
{402 * OVERSAMPLENR, 200},
|
||||
{410 * OVERSAMPLENR, 210},
|
||||
{418 * OVERSAMPLENR, 220},
|
||||
{426 * OVERSAMPLENR, 230},
|
||||
{432 * OVERSAMPLENR, 240},
|
||||
{440 * OVERSAMPLENR, 250},
|
||||
{448 * OVERSAMPLENR, 260},
|
||||
{454 * OVERSAMPLENR, 270},
|
||||
{462 * OVERSAMPLENR, 280},
|
||||
{469 * OVERSAMPLENR, 290},
|
||||
{475 * OVERSAMPLENR, 300},
|
||||
{483 * OVERSAMPLENR, 310},
|
||||
{491 * OVERSAMPLENR, 320},
|
||||
{499 * OVERSAMPLENR, 330},
|
||||
{505 * OVERSAMPLENR, 340},
|
||||
{513 * OVERSAMPLENR, 350},
|
||||
{519 * OVERSAMPLENR, 360},
|
||||
{527 * OVERSAMPLENR, 370},
|
||||
{533 * OVERSAMPLENR, 380},
|
||||
{541 * OVERSAMPLENR, 390},
|
||||
{549 * OVERSAMPLENR, 400},
|
||||
{616 * OVERSAMPLENR, 500},
|
||||
{682 * OVERSAMPLENR, 600},
|
||||
{741 * OVERSAMPLENR, 700},
|
||||
{801 * OVERSAMPLENR, 800},
|
||||
{856 * OVERSAMPLENR, 900},
|
||||
{910 * OVERSAMPLENR, 1000},
|
||||
{960 * OVERSAMPLENR, 1100},
|
||||
};
|
||||
#endif
|
||||
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORBED == 1010) // Pt1000 with 1k0 pullup
|
||||
const short temptable_1010[][2] PROGMEM = {
|
||||
PtLine(0,1000,1000)
|
||||
|
@ -1091,6 +1211,47 @@ const short temptable_1047[][2] PROGMEM = {
|
|||
};
|
||||
#endif
|
||||
|
||||
#if (THERMISTORAMBIENT == 2000) //100k thermistor NTCG104LH104JT1
|
||||
const short temptable_2000[][2] PROGMEM = {
|
||||
// Source: https://product.tdk.com/info/en/catalog/datasheets/503021/tpd_ntc-thermistor_ntcg_en.pdf
|
||||
// Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance
|
||||
{305*OVERSAMPLENR, 125},
|
||||
{338*OVERSAMPLENR, 120},
|
||||
{374*OVERSAMPLENR, 115},
|
||||
{412*OVERSAMPLENR, 110},
|
||||
{452*OVERSAMPLENR, 105},
|
||||
{494*OVERSAMPLENR, 100},
|
||||
{536*OVERSAMPLENR, 95},
|
||||
{580*OVERSAMPLENR, 90},
|
||||
{623*OVERSAMPLENR, 85},
|
||||
{665*OVERSAMPLENR, 80},
|
||||
{706*OVERSAMPLENR, 75},
|
||||
{744*OVERSAMPLENR, 70},
|
||||
{780*OVERSAMPLENR, 65},
|
||||
{813*OVERSAMPLENR, 60},
|
||||
{843*OVERSAMPLENR, 55},
|
||||
{869*OVERSAMPLENR, 50},
|
||||
{892*OVERSAMPLENR, 45},
|
||||
{912*OVERSAMPLENR, 40},
|
||||
{929*OVERSAMPLENR, 35},
|
||||
{943*OVERSAMPLENR, 30},
|
||||
{955*OVERSAMPLENR, 25},
|
||||
{965*OVERSAMPLENR, 20},
|
||||
{973*OVERSAMPLENR, 15},
|
||||
{979*OVERSAMPLENR, 10},
|
||||
{984*OVERSAMPLENR, 5},
|
||||
{988*OVERSAMPLENR, 0},
|
||||
{991*OVERSAMPLENR, -5},
|
||||
{993*OVERSAMPLENR, -10},
|
||||
{995*OVERSAMPLENR, -15},
|
||||
{996*OVERSAMPLENR, -20},
|
||||
{997*OVERSAMPLENR, -25},
|
||||
{998*OVERSAMPLENR, -30},
|
||||
{999*OVERSAMPLENR, -35},
|
||||
{999*OVERSAMPLENR, -40},
|
||||
};
|
||||
#endif
|
||||
|
||||
#define _TT_NAME(_N) temptable_ ## _N
|
||||
#define TT_NAME(_N) _TT_NAME(_N)
|
||||
|
||||
|
@ -1172,6 +1333,11 @@ const short temptable_1047[][2] PROGMEM = {
|
|||
# endif // BED_USES_THERMISTOR
|
||||
#endif
|
||||
|
||||
#ifdef THERMISTORAMBIENT
|
||||
# define AMBIENTTEMPTABLE TT_NAME(THERMISTORAMBIENT)
|
||||
# define AMBIENTTEMPTABLE_LEN (sizeof(AMBIENTTEMPTABLE)/sizeof(*AMBIENTTEMPTABLE))
|
||||
#endif
|
||||
|
||||
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
||||
#ifndef HEATER_BED_RAW_HI_TEMP
|
||||
# ifdef BED_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
||||
|
|
780
Firmware/tmc2130.cpp
Normal file
780
Firmware/tmc2130.cpp
Normal file
|
@ -0,0 +1,780 @@
|
|||
#include "Marlin.h"
|
||||
|
||||
#ifdef TMC2130
|
||||
|
||||
#include "tmc2130.h"
|
||||
#include <SPI.h>
|
||||
#include "LiquidCrystal.h"
|
||||
#include "ultralcd.h"
|
||||
|
||||
extern LiquidCrystal lcd;
|
||||
|
||||
#define TMC2130_GCONF_NORMAL 0x00000000 // spreadCycle
|
||||
#define TMC2130_GCONF_SGSENS 0x00003180 // spreadCycle with stallguard (stall activates DIAG0 and DIAG1 [pushpull])
|
||||
#define TMC2130_GCONF_SILENT 0x00000004 // stealthChop
|
||||
|
||||
//externals for debuging
|
||||
extern float current_position[4];
|
||||
extern void st_get_position_xy(long &x, long &y);
|
||||
extern long st_get_position(uint8_t axis);
|
||||
extern void crashdet_stop_and_save_print();
|
||||
extern void crashdet_stop_and_save_print2();
|
||||
|
||||
//chipselect pins
|
||||
uint8_t tmc2130_cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
|
||||
//diag pins
|
||||
uint8_t tmc2130_diag[4] = { X_TMC2130_DIAG, Y_TMC2130_DIAG, Z_TMC2130_DIAG, E0_TMC2130_DIAG };
|
||||
//mode
|
||||
uint8_t tmc2130_mode = TMC2130_MODE_NORMAL;
|
||||
//holding currents
|
||||
uint8_t tmc2130_current_h[4] = TMC2130_CURRENTS_H;
|
||||
//running currents
|
||||
uint8_t tmc2130_current_r[4] = TMC2130_CURRENTS_R;
|
||||
//axis stalled flags
|
||||
uint8_t tmc2130_axis_stalled[4] = {0, 0, 0, 0};
|
||||
|
||||
//running currents for homing
|
||||
uint8_t tmc2130_current_r_home[4] = {10, 10, 20, 10};
|
||||
|
||||
|
||||
//pwm_ampl
|
||||
uint8_t tmc2130_pwm_ampl[2] = {TMC2130_PWM_AMPL_X, TMC2130_PWM_AMPL_Y};
|
||||
//pwm_grad
|
||||
uint8_t tmc2130_pwm_grad[2] = {TMC2130_PWM_GRAD_X, TMC2130_PWM_GRAD_Y};
|
||||
//pwm_auto
|
||||
uint8_t tmc2130_pwm_auto[2] = {TMC2130_PWM_AUTO_X, TMC2130_PWM_AUTO_Y};
|
||||
//pwm_freq
|
||||
uint8_t tmc2130_pwm_freq[2] = {TMC2130_PWM_FREQ_X, TMC2130_PWM_FREQ_Y};
|
||||
|
||||
uint8_t tmc2130_mres[4] = {0, 0, 0, 0}; //will be filed at begin of init
|
||||
|
||||
|
||||
uint8_t tmc2130_sg_thr[4] = {TMC2130_SG_THRS_X, TMC2130_SG_THRS_Y, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E};
|
||||
uint8_t tmc2130_sg_thr_home[4] = {3, 3, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E};
|
||||
|
||||
uint32_t tmc2130_sg_pos[4] = {0, 0, 0, 0};
|
||||
|
||||
uint8_t sg_homing_axes_mask = 0x00;
|
||||
|
||||
uint8_t tmc2130_sg_meassure = 0xff;
|
||||
uint16_t tmc2130_sg_meassure_cnt = 0;
|
||||
uint32_t tmc2130_sg_meassure_val = 0;
|
||||
|
||||
|
||||
bool tmc2130_sg_stop_on_crash = true;
|
||||
bool tmc2130_sg_crash = false;
|
||||
uint8_t tmc2130_diag_mask = 0x00;
|
||||
uint16_t tmc2130_sg_err[4] = {0, 0, 0, 0};
|
||||
uint16_t tmc2130_sg_cnt[4] = {0, 0, 0, 0};
|
||||
bool tmc2130_sg_change = false;
|
||||
|
||||
|
||||
bool skip_debug_msg = false;
|
||||
|
||||
//TMC2130 registers
|
||||
#define TMC2130_REG_GCONF 0x00 // 17 bits
|
||||
#define TMC2130_REG_GSTAT 0x01 // 3 bits
|
||||
#define TMC2130_REG_IOIN 0x04 // 8+8 bits
|
||||
#define TMC2130_REG_IHOLD_IRUN 0x10 // 5+5+4 bits
|
||||
#define TMC2130_REG_TPOWERDOWN 0x11 // 8 bits
|
||||
#define TMC2130_REG_TSTEP 0x12 // 20 bits
|
||||
#define TMC2130_REG_TPWMTHRS 0x13 // 20 bits
|
||||
#define TMC2130_REG_TCOOLTHRS 0x14 // 20 bits
|
||||
#define TMC2130_REG_THIGH 0x15 // 20 bits
|
||||
#define TMC2130_REG_XDIRECT 0x2d // 32 bits
|
||||
#define TMC2130_REG_VDCMIN 0x33 // 23 bits
|
||||
#define TMC2130_REG_MSLUT0 0x60 // 32 bits
|
||||
#define TMC2130_REG_MSLUT1 0x61 // 32 bits
|
||||
#define TMC2130_REG_MSLUT2 0x62 // 32 bits
|
||||
#define TMC2130_REG_MSLUT3 0x63 // 32 bits
|
||||
#define TMC2130_REG_MSLUT4 0x64 // 32 bits
|
||||
#define TMC2130_REG_MSLUT5 0x65 // 32 bits
|
||||
#define TMC2130_REG_MSLUT6 0x66 // 32 bits
|
||||
#define TMC2130_REG_MSLUT7 0x67 // 32 bits
|
||||
#define TMC2130_REG_MSLUTSEL 0x68 // 32 bits
|
||||
#define TMC2130_REG_MSLUTSTART 0x69 // 8+8 bits
|
||||
#define TMC2130_REG_MSCNT 0x6a // 10 bits
|
||||
#define TMC2130_REG_MSCURACT 0x6b // 9+9 bits
|
||||
#define TMC2130_REG_CHOPCONF 0x6c // 32 bits
|
||||
#define TMC2130_REG_COOLCONF 0x6d // 25 bits
|
||||
#define TMC2130_REG_DCCTRL 0x6e // 24 bits
|
||||
#define TMC2130_REG_DRV_STATUS 0x6f // 32 bits
|
||||
#define TMC2130_REG_PWMCONF 0x70 // 22 bits
|
||||
#define TMC2130_REG_PWM_SCALE 0x71 // 8 bits
|
||||
#define TMC2130_REG_ENCM_CTRL 0x72 // 2 bits
|
||||
#define TMC2130_REG_LOST_STEPS 0x73 // 20 bits
|
||||
|
||||
|
||||
uint16_t tmc2130_rd_TSTEP(uint8_t cs);
|
||||
uint16_t tmc2130_rd_MSCNT(uint8_t cs);
|
||||
uint16_t tmc2130_rd_DRV_STATUS(uint8_t cs);
|
||||
|
||||
void tmc2130_wr_CHOPCONF(uint8_t cs, uint8_t toff = 3, uint8_t hstrt = 4, uint8_t hend = 1, uint8_t fd3 = 0, uint8_t disfdcc = 0, uint8_t rndtf = 0, uint8_t chm = 0, uint8_t tbl = 2, uint8_t vsense = 0, uint8_t vhighfs = 0, uint8_t vhighchm = 0, uint8_t sync = 0, uint8_t mres = 0b0100, uint8_t intpol = 1, uint8_t dedge = 0, uint8_t diss2g = 0);
|
||||
void tmc2130_wr_PWMCONF(uint8_t cs, uint8_t pwm_ampl, uint8_t pwm_grad, uint8_t pwm_freq, uint8_t pwm_auto, uint8_t pwm_symm, uint8_t freewheel);
|
||||
void tmc2130_wr_TPWMTHRS(uint8_t cs, uint32_t val32);
|
||||
void tmc2130_wr_THIGH(uint8_t cs, uint32_t val32);
|
||||
|
||||
uint8_t tmc2130_axis_by_cs(uint8_t cs);
|
||||
uint8_t tmc2130_calc_mres(uint16_t microstep_resolution);
|
||||
|
||||
uint8_t tmc2130_wr(uint8_t cs, uint8_t addr, uint32_t wval);
|
||||
uint8_t tmc2130_rd(uint8_t cs, uint8_t addr, uint32_t* rval);
|
||||
uint8_t tmc2130_txrx(uint8_t cs, uint8_t addr, uint32_t wval, uint32_t* rval);
|
||||
|
||||
|
||||
void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_t current_r);
|
||||
|
||||
|
||||
|
||||
void tmc2130_init()
|
||||
{
|
||||
tmc2130_mres[0] = tmc2130_calc_mres(TMC2130_USTEPS_XY);
|
||||
tmc2130_mres[1] = tmc2130_calc_mres(TMC2130_USTEPS_XY);
|
||||
tmc2130_mres[2] = tmc2130_calc_mres(TMC2130_USTEPS_Z);
|
||||
tmc2130_mres[3] = tmc2130_calc_mres(TMC2130_USTEPS_E);
|
||||
MYSERIAL.print("tmc2130_init mode=");
|
||||
MYSERIAL.println(tmc2130_mode, DEC);
|
||||
WRITE(X_TMC2130_CS, HIGH);
|
||||
WRITE(Y_TMC2130_CS, HIGH);
|
||||
WRITE(Z_TMC2130_CS, HIGH);
|
||||
WRITE(E0_TMC2130_CS, HIGH);
|
||||
SET_OUTPUT(X_TMC2130_CS);
|
||||
SET_OUTPUT(Y_TMC2130_CS);
|
||||
SET_OUTPUT(Z_TMC2130_CS);
|
||||
SET_OUTPUT(E0_TMC2130_CS);
|
||||
SET_INPUT(X_TMC2130_DIAG);
|
||||
SET_INPUT(Y_TMC2130_DIAG);
|
||||
SET_INPUT(Z_TMC2130_DIAG);
|
||||
SET_INPUT(E0_TMC2130_DIAG);
|
||||
SPI.begin();
|
||||
for (int axis = 0; axis < 2; axis++) // X Y axes
|
||||
{
|
||||
/* if (tmc2130_current_r[axis] <= 31)
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(tmc2130_cs[axis], 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, TMC2130_INTPOL_XY, 0, 0);
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
||||
}
|
||||
else
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(tmc2130_cs[axis], 3, 5, 1, 0, 0, 0, 0, 2, 0, 0, 0, 0, mres, TMC2130_INTPOL_XY, 0, 0);
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((tmc2130_current_r[axis] >> 1) & 0x1f) << 8) | ((tmc2130_current_h[axis] >> 1) & 0x1f));
|
||||
}*/
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
|
||||
|
||||
// tmc2130_wr_CHOPCONF(tmc2130_cs[axis], 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, TMC2130_INTPOL_XY, 0, 0);
|
||||
// tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
||||
// tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_COOLCONF, (((uint32_t)tmc2130_sg_thr[axis]) << 16) | ((uint32_t)1 << 24));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_COOLCONF, (((uint32_t)tmc2130_sg_thr[axis]) << 16));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_TCOOLTHRS, (tmc2130_mode == TMC2130_MODE_SILENT)?0:((axis==X_AXIS)?TMC2130_TCOOLTHRS_X:TMC2130_TCOOLTHRS_Y));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, (tmc2130_mode == TMC2130_MODE_SILENT)?TMC2130_GCONF_SILENT:TMC2130_GCONF_SGSENS);
|
||||
tmc2130_wr_PWMCONF(tmc2130_cs[axis], tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0);
|
||||
tmc2130_wr_TPWMTHRS(tmc2130_cs[axis], TMC2130_TPWMTHRS);
|
||||
//tmc2130_wr_THIGH(tmc2130_cs[axis], TMC2130_THIGH);
|
||||
}
|
||||
for (int axis = 2; axis < 3; axis++) // Z axis
|
||||
{
|
||||
// uint8_t mres = tmc2130_mres(TMC2130_USTEPS_Z);
|
||||
/* if (tmc2130_current_r[axis] <= 31)
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(tmc2130_cs[axis], 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, TMC2130_INTPOL_Z, 0, 0);
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
||||
}
|
||||
else
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(tmc2130_cs[axis], 3, 5, 1, 0, 0, 0, 0, 2, 0, 0, 0, 0, mres, TMC2130_INTPOL_Z, 0, 0);
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((tmc2130_current_r[axis] >> 1) & 0x1f) << 8) | ((tmc2130_current_h[axis] >> 1) & 0x1f));
|
||||
}*/
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
|
||||
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS);
|
||||
}
|
||||
for (int axis = 3; axis < 4; axis++) // E axis
|
||||
{
|
||||
// uint8_t mres = tmc2130_mres(TMC2130_USTEPS_E);
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
|
||||
|
||||
// tmc2130_wr_CHOPCONF(tmc2130_cs[axis], 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, TMC2130_INTPOL_E, 0, 0);
|
||||
// tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((tmc2130_current_r[axis] & 0x1f) << 8) | (tmc2130_current_h[axis] & 0x1f));
|
||||
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_TPOWERDOWN, 0x00000000);
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS);
|
||||
}
|
||||
|
||||
tmc2130_sg_err[0] = 0;
|
||||
tmc2130_sg_err[1] = 0;
|
||||
tmc2130_sg_err[2] = 0;
|
||||
tmc2130_sg_err[3] = 0;
|
||||
tmc2130_sg_cnt[0] = 0;
|
||||
tmc2130_sg_cnt[1] = 0;
|
||||
tmc2130_sg_cnt[2] = 0;
|
||||
tmc2130_sg_cnt[3] = 0;
|
||||
}
|
||||
|
||||
uint8_t tmc2130_sample_diag()
|
||||
{
|
||||
uint8_t mask = 0;
|
||||
if (READ(X_TMC2130_DIAG)) mask |= X_AXIS_MASK;
|
||||
if (READ(Y_TMC2130_DIAG)) mask |= Y_AXIS_MASK;
|
||||
// if (READ(Z_TMC2130_DIAG)) mask |= Z_AXIS_MASK;
|
||||
// if (READ(E0_TMC2130_DIAG)) mask |= E_AXIS_MASK;
|
||||
return mask;
|
||||
}
|
||||
|
||||
void tmc2130_st_isr(uint8_t last_step_mask)
|
||||
{
|
||||
if (tmc2130_mode == TMC2130_MODE_SILENT || tmc2130_sg_stop_on_crash == false) return;
|
||||
bool crash = false;
|
||||
uint8_t diag_mask = tmc2130_sample_diag();
|
||||
// for (uint8_t axis = X_AXIS; axis <= E_AXIS; axis++)
|
||||
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++)
|
||||
{
|
||||
uint8_t mask = (X_AXIS_MASK << axis);
|
||||
if (diag_mask & mask) tmc2130_sg_err[axis]++;
|
||||
else
|
||||
if (tmc2130_sg_err[axis] > 0) tmc2130_sg_err[axis]--;
|
||||
if (tmc2130_sg_cnt[axis] < tmc2130_sg_err[axis])
|
||||
{
|
||||
tmc2130_sg_cnt[axis] = tmc2130_sg_err[axis];
|
||||
tmc2130_sg_change = true;
|
||||
if (tmc2130_sg_err[axis] >= 64)
|
||||
{
|
||||
tmc2130_sg_err[axis] = 0;
|
||||
crash = true;
|
||||
}
|
||||
}
|
||||
// if ((diag_mask & mask)/* && !(tmc2130_diag_mask & mask)*/)
|
||||
// crash = true;
|
||||
}
|
||||
tmc2130_diag_mask = diag_mask;
|
||||
if (sg_homing_axes_mask == 0)
|
||||
{
|
||||
/* if (crash)
|
||||
{
|
||||
if (diag_mask & 0x01) tmc2130_sg_cnt[0]++;
|
||||
if (diag_mask & 0x02) tmc2130_sg_cnt[1]++;
|
||||
if (diag_mask & 0x04) tmc2130_sg_cnt[2]++;
|
||||
if (diag_mask & 0x08) tmc2130_sg_cnt[3]++;
|
||||
}*/
|
||||
if (tmc2130_sg_stop_on_crash && crash)
|
||||
{
|
||||
tmc2130_sg_crash = true;
|
||||
tmc2130_sg_stop_on_crash = false;
|
||||
crashdet_stop_and_save_print();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void tmc2130_update_sg_axis(uint8_t axis)
|
||||
{
|
||||
if (!tmc2130_axis_stalled[axis])
|
||||
{
|
||||
uint8_t cs = tmc2130_cs[axis];
|
||||
uint16_t tstep = tmc2130_rd_TSTEP(cs);
|
||||
if (tstep < TMC2130_TCOOLTHRS_Z)
|
||||
{
|
||||
long pos = st_get_position(axis);
|
||||
if (abs(pos - tmc2130_sg_pos[axis]) > TMC2130_SG_DELTA)
|
||||
{
|
||||
uint16_t sg = tmc2130_rd_DRV_STATUS(cs) & 0x3ff;
|
||||
if (sg == 0)
|
||||
tmc2130_axis_stalled[axis] = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool tmc2130_update_sg()
|
||||
{
|
||||
// uint16_t tstep = tmc2130_rd_TSTEP(tmc2130_cs[0]);
|
||||
// MYSERIAL.print("TSTEP_X=");
|
||||
// MYSERIAL.println((int)tstep);
|
||||
if (tmc2130_sg_meassure <= E_AXIS)
|
||||
{
|
||||
uint8_t cs = tmc2130_cs[tmc2130_sg_meassure];
|
||||
uint16_t sg = tmc2130_rd_DRV_STATUS(cs) & 0x3ff;
|
||||
tmc2130_sg_meassure_val += sg;
|
||||
tmc2130_sg_meassure_cnt++;
|
||||
|
||||
// printf_P(PSTR("tmc2130_update_sg - meassure - sg=%d\n"), sg);
|
||||
return true;
|
||||
}
|
||||
#ifdef TMC2130_SG_HOMING_SW_XY
|
||||
if (sg_homing_axes_mask & X_AXIS_MASK) tmc2130_update_sg_axis(X_AXIS);
|
||||
if (sg_homing_axes_mask & Y_AXIS_MASK) tmc2130_update_sg_axis(Y_AXIS);
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
#ifdef TMC2130_SG_HOMING_SW_Z
|
||||
if (sg_homing_axes_mask & Z_AXIS_MASK) tmc2130_update_sg_axis(Z_AXIS);
|
||||
#endif //TMC2130_SG_HOMING_SW_Z
|
||||
#if (defined(TMC2130_SG_HOMING) && defined(TMC2130_SG_HOMING_SW_XY))
|
||||
if (sg_homing_axes_mask == 0) return false;
|
||||
#ifdef TMC2130_DEBUG
|
||||
MYSERIAL.print("tmc2130_update_sg mask=0x");
|
||||
MYSERIAL.print((int)sg_homing_axes_mask, 16);
|
||||
MYSERIAL.print(" stalledX=");
|
||||
MYSERIAL.print((int)tmc2130_axis_stalled[0]);
|
||||
MYSERIAL.print(" stalledY=");
|
||||
MYSERIAL.println((int)tmc2130_axis_stalled[1]);
|
||||
#endif //TMC2130_DEBUG
|
||||
for (uint8_t axis = X_AXIS; axis <= Y_AXIS; axis++) //only X and Y axes
|
||||
{
|
||||
uint8_t mask = (X_AXIS_MASK << axis);
|
||||
if (sg_homing_axes_mask & mask)
|
||||
{
|
||||
if (!tmc2130_axis_stalled[axis])
|
||||
{
|
||||
uint8_t cs = tmc2130_cs[axis];
|
||||
uint16_t tstep = tmc2130_rd_TSTEP(cs);
|
||||
if (tstep < TMC2130_TCOOLTHRS)
|
||||
{
|
||||
long pos = st_get_position(axis);
|
||||
if (abs(pos - tmc2130_sg_pos[axis]) > TMC2130_SG_DELTA)
|
||||
{
|
||||
uint16_t sg = tmc2130_rd_DRV_STATUS(cs) & 0x3ff;
|
||||
if (sg == 0)
|
||||
{
|
||||
tmc2130_axis_stalled[axis] = true;
|
||||
#ifdef TMC2130_DEBUG
|
||||
MYSERIAL.print("tmc2130_update_sg AXIS STALLED ");
|
||||
MYSERIAL.println((int)axis);
|
||||
#endif //TMC2130_DEBUG
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
void tmc2130_home_enter(uint8_t axes_mask)
|
||||
{
|
||||
#ifdef TMC2130_DEBUG
|
||||
MYSERIAL.print("tmc2130_home_enter mask=0x");
|
||||
MYSERIAL.println((int)axes_mask, 16);
|
||||
#endif //TMC2130_DEBUG
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) //X Y and Z axes
|
||||
{
|
||||
uint8_t mask = (X_AXIS_MASK << axis);
|
||||
uint8_t cs = tmc2130_cs[axis];
|
||||
if (axes_mask & mask)
|
||||
{
|
||||
sg_homing_axes_mask |= mask;
|
||||
tmc2130_sg_pos[axis] = st_get_position(axis);
|
||||
tmc2130_axis_stalled[axis] = false;
|
||||
//Configuration to spreadCycle
|
||||
tmc2130_wr(cs, TMC2130_REG_GCONF, TMC2130_GCONF_NORMAL);
|
||||
tmc2130_wr(cs, TMC2130_REG_COOLCONF, (((uint32_t)tmc2130_sg_thr_home[axis]) << 16));
|
||||
// tmc2130_wr(cs, TMC2130_REG_COOLCONF, (((uint32_t)tmc2130_sg_thr[axis]) << 16) | ((uint32_t)1 << 24));
|
||||
tmc2130_wr(cs, TMC2130_REG_TCOOLTHRS, (axis==X_AXIS)?TMC2130_TCOOLTHRS_X:TMC2130_TCOOLTHRS_Y);
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r_home[axis]);
|
||||
#ifndef TMC2130_SG_HOMING_SW_XY
|
||||
if (mask & (X_AXIS_MASK | Y_AXIS_MASK))
|
||||
tmc2130_wr(cs, TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS); //stallguard output DIAG1, DIAG1 = pushpull
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
}
|
||||
}
|
||||
#endif //TMC2130_SG_HOMING
|
||||
}
|
||||
|
||||
void tmc2130_home_exit()
|
||||
{
|
||||
#ifdef TMC2130_DEBUG
|
||||
MYSERIAL.print("tmc2130_home_exit mask=0x");
|
||||
MYSERIAL.println((int)sg_homing_axes_mask, 16);
|
||||
#endif //TMC2130_DEBUG
|
||||
#ifdef TMC2130_SG_HOMING
|
||||
if (sg_homing_axes_mask)
|
||||
{
|
||||
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) //X Y and Z axes
|
||||
{
|
||||
uint8_t mask = (X_AXIS_MASK << axis);
|
||||
if (sg_homing_axes_mask & mask & (X_AXIS_MASK | Y_AXIS_MASK))
|
||||
{
|
||||
if (tmc2130_mode == TMC2130_MODE_SILENT)
|
||||
{
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SILENT); // Configuration back to stealthChop
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_TCOOLTHRS, 0);
|
||||
// tmc2130_wr_PWMCONF(tmc2130_cs[i], tmc2130_pwm_ampl[i], tmc2130_pwm_grad[i], tmc2130_pwm_freq[i], tmc2130_pwm_auto[i], 0, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef TMC2130_SG_HOMING_SW_XY
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_NORMAL);
|
||||
#else //TMC2130_SG_HOMING_SW_XY
|
||||
// tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_NORMAL);
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
|
||||
// tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_COOLCONF, (((uint32_t)tmc2130_sg_thr[axis]) << 16) | ((uint32_t)1 << 24));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_COOLCONF, (((uint32_t)tmc2130_sg_thr[axis]) << 16));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_TCOOLTHRS, (tmc2130_mode == TMC2130_MODE_SILENT)?0:((axis==X_AXIS)?TMC2130_TCOOLTHRS_X:TMC2130_TCOOLTHRS_Y));
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS);
|
||||
#endif //TMC2130_SG_HOMING_SW_XY
|
||||
}
|
||||
}
|
||||
tmc2130_axis_stalled[axis] = false;
|
||||
}
|
||||
sg_homing_axes_mask = 0x00;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void tmc2130_home_pause(uint8_t axis)
|
||||
{
|
||||
if (tmc2130_mode == TMC2130_MODE_NORMAL)
|
||||
{
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_NORMAL);
|
||||
}
|
||||
}
|
||||
|
||||
void tmc2130_home_resume(uint8_t axis)
|
||||
{
|
||||
if (tmc2130_mode == TMC2130_MODE_NORMAL)
|
||||
{
|
||||
tmc2130_wr(tmc2130_cs[axis], TMC2130_REG_GCONF, TMC2130_GCONF_SGSENS);
|
||||
}
|
||||
}
|
||||
|
||||
void tmc2130_home_restart(uint8_t axis)
|
||||
{
|
||||
tmc2130_sg_pos[axis] = st_get_position(axis);
|
||||
tmc2130_axis_stalled[axis] = false;
|
||||
}
|
||||
|
||||
void tmc2130_sg_meassure_start(uint8_t axis)
|
||||
{
|
||||
tmc2130_sg_meassure = axis;
|
||||
tmc2130_sg_meassure_cnt = 0;
|
||||
tmc2130_sg_meassure_val = 0;
|
||||
}
|
||||
|
||||
uint16_t tmc2130_sg_meassure_stop()
|
||||
{
|
||||
tmc2130_sg_meassure = 0xff;
|
||||
return tmc2130_sg_meassure_val / tmc2130_sg_meassure_cnt;
|
||||
}
|
||||
|
||||
|
||||
bool tmc2130_wait_standstill_xy(int timeout)
|
||||
{
|
||||
// MYSERIAL.println("tmc2130_wait_standstill_xy");
|
||||
bool standstill = false;
|
||||
while (!standstill && (timeout > 0))
|
||||
{
|
||||
uint32_t drv_status_x = 0;
|
||||
uint32_t drv_status_y = 0;
|
||||
tmc2130_rd(tmc2130_cs[X_AXIS], TMC2130_REG_DRV_STATUS, &drv_status_x);
|
||||
tmc2130_rd(tmc2130_cs[Y_AXIS], TMC2130_REG_DRV_STATUS, &drv_status_y);
|
||||
/* MYSERIAL.print(timeout, 10);
|
||||
MYSERIAL.println(' ');
|
||||
MYSERIAL.print(drv_status_x, 16);
|
||||
MYSERIAL.println(' ');
|
||||
MYSERIAL.print(drv_status_y, 16);
|
||||
MYSERIAL.println('#');*/
|
||||
standstill = (drv_status_x & 0x80000000) && (drv_status_y & 0x80000000);
|
||||
tmc2130_check_overtemp();
|
||||
timeout--;
|
||||
}
|
||||
return standstill;
|
||||
}
|
||||
|
||||
|
||||
void tmc2130_check_overtemp()
|
||||
{
|
||||
const static char TMC_OVERTEMP_MSG[] PROGMEM = "TMC DRIVER OVERTEMP ";
|
||||
static uint32_t checktime = 0;
|
||||
if (millis() - checktime > 1000 )
|
||||
{
|
||||
// MYSERIAL.print("DRV_STATUS ");
|
||||
for (int i = 0; i < 4; i++)
|
||||
{
|
||||
uint32_t drv_status = 0;
|
||||
skip_debug_msg = true;
|
||||
tmc2130_rd(tmc2130_cs[i], TMC2130_REG_DRV_STATUS, &drv_status);
|
||||
/* MYSERIAL.print(i, DEC);
|
||||
MYSERIAL.print(' ');
|
||||
MYSERIAL.print(drv_status, 16);*/
|
||||
|
||||
if (drv_status & ((uint32_t)1 << 26))
|
||||
{ // BIT 26 - over temp prewarning ~120C (+-20C)
|
||||
SERIAL_ERRORRPGM(TMC_OVERTEMP_MSG);
|
||||
SERIAL_ECHOLN(i);
|
||||
for (int j = 0; j < 4; j++)
|
||||
tmc2130_wr(tmc2130_cs[j], TMC2130_REG_CHOPCONF, 0x00010000);
|
||||
kill(TMC_OVERTEMP_MSG);
|
||||
}
|
||||
|
||||
}
|
||||
// MYSERIAL.println('#');
|
||||
checktime = millis();
|
||||
tmc2130_sg_change = true;
|
||||
}
|
||||
#ifdef DEBUG_CRASHDET_COUNTERS
|
||||
if (tmc2130_sg_change)
|
||||
{
|
||||
for (int i = 0; i < 4; i++)
|
||||
{
|
||||
tmc2130_sg_change = false;
|
||||
lcd.setCursor(0 + i*4, 3);
|
||||
lcd.print(itostr3(tmc2130_sg_cnt[i]));
|
||||
lcd.print(' ');
|
||||
}
|
||||
}
|
||||
#endif DEBUG_CRASHDET_COUNTERS
|
||||
}
|
||||
|
||||
void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_t current_r)
|
||||
{
|
||||
uint8_t cs = tmc2130_cs[axis];
|
||||
uint8_t intpol = 1;
|
||||
if (current_r <= 31)
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(cs, 3, 5, 1, 0, 0, 0, 0, 2, 1, 0, 0, 0, mres, intpol, 0, 0);
|
||||
tmc2130_wr(cs, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((current_r & 0x1f) << 8) | (current_h & 0x1f));
|
||||
}
|
||||
else
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(cs, 3, 5, 1, 0, 0, 0, 0, 2, 0, 0, 0, 0, mres, intpol, 0, 0);
|
||||
tmc2130_wr(cs, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((current_r >> 1) & 0x1f) << 8) | ((current_h >> 1) & 0x1f));
|
||||
}
|
||||
}
|
||||
|
||||
void tmc2130_set_current_h(uint8_t axis, uint8_t current)
|
||||
{
|
||||
MYSERIAL.print("tmc2130_set_current_h ");
|
||||
MYSERIAL.print((int)axis);
|
||||
MYSERIAL.print(" ");
|
||||
MYSERIAL.println((int)current);
|
||||
tmc2130_current_h[axis] = current;
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
|
||||
}
|
||||
|
||||
void tmc2130_set_current_r(uint8_t axis, uint8_t current)
|
||||
{
|
||||
MYSERIAL.print("tmc2130_set_current_r ");
|
||||
MYSERIAL.print((int)axis);
|
||||
MYSERIAL.print(" ");
|
||||
MYSERIAL.println((int)current);
|
||||
tmc2130_current_r[axis] = current;
|
||||
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
|
||||
}
|
||||
|
||||
void tmc2130_print_currents()
|
||||
{
|
||||
MYSERIAL.println("tmc2130_print_currents");
|
||||
MYSERIAL.println("\tH\rR");
|
||||
MYSERIAL.print("X\t");
|
||||
MYSERIAL.print((int)tmc2130_current_h[0]);
|
||||
MYSERIAL.print("\t");
|
||||
MYSERIAL.println((int)tmc2130_current_r[0]);
|
||||
MYSERIAL.print("Y\t");
|
||||
MYSERIAL.print((int)tmc2130_current_h[1]);
|
||||
MYSERIAL.print("\t");
|
||||
MYSERIAL.println((int)tmc2130_current_r[1]);
|
||||
MYSERIAL.print("Z\t");
|
||||
MYSERIAL.print((int)tmc2130_current_h[2]);
|
||||
MYSERIAL.print("\t");
|
||||
MYSERIAL.println((int)tmc2130_current_r[2]);
|
||||
MYSERIAL.print("E\t");
|
||||
MYSERIAL.print((int)tmc2130_current_h[3]);
|
||||
MYSERIAL.print("\t");
|
||||
MYSERIAL.println((int)tmc2130_current_r[3]);
|
||||
}
|
||||
|
||||
void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl)
|
||||
{
|
||||
MYSERIAL.print("tmc2130_set_pwm_ampl ");
|
||||
MYSERIAL.print((int)axis);
|
||||
MYSERIAL.print(" ");
|
||||
MYSERIAL.println((int)pwm_ampl);
|
||||
tmc2130_pwm_ampl[axis] = pwm_ampl;
|
||||
if (((axis == 0) || (axis == 1)) && (tmc2130_mode == TMC2130_MODE_SILENT))
|
||||
tmc2130_wr_PWMCONF(tmc2130_cs[axis], tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0);
|
||||
}
|
||||
|
||||
void tmc2130_set_pwm_grad(uint8_t axis, uint8_t pwm_grad)
|
||||
{
|
||||
MYSERIAL.print("tmc2130_set_pwm_grad ");
|
||||
MYSERIAL.print((int)axis);
|
||||
MYSERIAL.print(" ");
|
||||
MYSERIAL.println((int)pwm_grad);
|
||||
tmc2130_pwm_grad[axis] = pwm_grad;
|
||||
if (((axis == 0) || (axis == 1)) && (tmc2130_mode == TMC2130_MODE_SILENT))
|
||||
tmc2130_wr_PWMCONF(tmc2130_cs[axis], tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0);
|
||||
}
|
||||
|
||||
uint16_t tmc2130_rd_TSTEP(uint8_t cs)
|
||||
{
|
||||
uint32_t val32 = 0;
|
||||
tmc2130_rd(cs, TMC2130_REG_TSTEP, &val32);
|
||||
if (val32 & 0x000f0000) return 0xffff;
|
||||
return val32 & 0xffff;
|
||||
}
|
||||
|
||||
uint16_t tmc2130_rd_MSCNT(uint8_t cs)
|
||||
{
|
||||
uint32_t val32 = 0;
|
||||
tmc2130_rd(cs, TMC2130_REG_MSCNT, &val32);
|
||||
return val32 & 0x3ff;
|
||||
}
|
||||
|
||||
uint16_t tmc2130_rd_DRV_STATUS(uint8_t cs)
|
||||
{
|
||||
uint32_t val32 = 0;
|
||||
tmc2130_rd(cs, TMC2130_REG_DRV_STATUS, &val32);
|
||||
return val32;
|
||||
}
|
||||
|
||||
void tmc2130_wr_CHOPCONF(uint8_t cs, uint8_t toff, uint8_t hstrt, uint8_t hend, uint8_t fd3, uint8_t disfdcc, uint8_t rndtf, uint8_t chm, uint8_t tbl, uint8_t vsense, uint8_t vhighfs, uint8_t vhighchm, uint8_t sync, uint8_t mres, uint8_t intpol, uint8_t dedge, uint8_t diss2g)
|
||||
{
|
||||
uint32_t val = 0;
|
||||
val |= (uint32_t)(toff & 15);
|
||||
val |= (uint32_t)(hstrt & 7) << 4;
|
||||
val |= (uint32_t)(hend & 15) << 7;
|
||||
val |= (uint32_t)(fd3 & 1) << 11;
|
||||
val |= (uint32_t)(disfdcc & 1) << 12;
|
||||
val |= (uint32_t)(rndtf & 1) << 13;
|
||||
val |= (uint32_t)(chm & 1) << 14;
|
||||
val |= (uint32_t)(tbl & 3) << 15;
|
||||
val |= (uint32_t)(vsense & 1) << 17;
|
||||
val |= (uint32_t)(vhighfs & 1) << 18;
|
||||
val |= (uint32_t)(vhighchm & 1) << 19;
|
||||
val |= (uint32_t)(sync & 15) << 20;
|
||||
val |= (uint32_t)(mres & 15) << 24;
|
||||
val |= (uint32_t)(intpol & 1) << 28;
|
||||
val |= (uint32_t)(dedge & 1) << 29;
|
||||
val |= (uint32_t)(diss2g & 1) << 30;
|
||||
tmc2130_wr(cs, TMC2130_REG_CHOPCONF, val);
|
||||
}
|
||||
|
||||
//void tmc2130_wr_PWMCONF(uint8_t cs, uint8_t PWMautoScale, uint8_t PWMfreq, uint8_t PWMgrad, uint8_t PWMampl)
|
||||
void tmc2130_wr_PWMCONF(uint8_t cs, uint8_t pwm_ampl, uint8_t pwm_grad, uint8_t pwm_freq, uint8_t pwm_auto, uint8_t pwm_symm, uint8_t freewheel)
|
||||
{
|
||||
uint32_t val = 0;
|
||||
val |= (uint32_t)(pwm_ampl & 255);
|
||||
val |= (uint32_t)(pwm_grad & 255) << 8;
|
||||
val |= (uint32_t)(pwm_freq & 3) << 16;
|
||||
val |= (uint32_t)(pwm_auto & 1) << 18;
|
||||
val |= (uint32_t)(pwm_symm & 1) << 19;
|
||||
val |= (uint32_t)(freewheel & 3) << 20;
|
||||
tmc2130_wr(cs, TMC2130_REG_PWMCONF, val);
|
||||
// tmc2130_wr(cs, TMC2130_REG_PWMCONF, ((uint32_t)(PWMautoScale+PWMfreq) << 16) | ((uint32_t)PWMgrad << 8) | PWMampl); // TMC LJ -> For better readability changed to 0x00 and added PWMautoScale and PWMfreq
|
||||
}
|
||||
|
||||
void tmc2130_wr_TPWMTHRS(uint8_t cs, uint32_t val32)
|
||||
{
|
||||
tmc2130_wr(cs, TMC2130_REG_TPWMTHRS, val32);
|
||||
}
|
||||
|
||||
void tmc2130_wr_THIGH(uint8_t cs, uint32_t val32)
|
||||
{
|
||||
tmc2130_wr(cs, TMC2130_REG_THIGH, val32);
|
||||
}
|
||||
|
||||
#if defined(TMC2130_DEBUG_RD) || defined(TMC2130_DEBUG_WR)
|
||||
uint8_t tmc2130_axis_by_cs(uint8_t cs)
|
||||
{
|
||||
switch (cs)
|
||||
{
|
||||
case X_TMC2130_CS: return 0;
|
||||
case Y_TMC2130_CS: return 1;
|
||||
case Z_TMC2130_CS: return 2;
|
||||
case E0_TMC2130_CS: return 3;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
#endif //TMC2130_DEBUG
|
||||
|
||||
uint8_t tmc2130_calc_mres(uint16_t microstep_resolution)
|
||||
{
|
||||
if (microstep_resolution == 256) return 0b0000;
|
||||
if (microstep_resolution == 128) return 0b0001;
|
||||
if (microstep_resolution == 64) return 0b0010;
|
||||
if (microstep_resolution == 32) return 0b0011;
|
||||
if (microstep_resolution == 16) return 0b0100;
|
||||
if (microstep_resolution == 8) return 0b0101;
|
||||
if (microstep_resolution == 4) return 0b0110;
|
||||
if (microstep_resolution == 2) return 0b0111;
|
||||
if (microstep_resolution == 1) return 0b1000;
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t tmc2130_wr(uint8_t cs, uint8_t addr, uint32_t wval)
|
||||
{
|
||||
uint8_t stat = tmc2130_txrx(cs, addr | 0x80, wval, 0);
|
||||
#ifdef TMC2130_DEBUG_WR
|
||||
MYSERIAL.print("tmc2130_wr(");
|
||||
MYSERIAL.print((unsigned char)tmc2130_axis_by_cs(cs), DEC);
|
||||
MYSERIAL.print(", 0x");
|
||||
MYSERIAL.print((unsigned char)addr, HEX);
|
||||
MYSERIAL.print(", 0x");
|
||||
MYSERIAL.print((unsigned long)wval, HEX);
|
||||
MYSERIAL.print(")=0x");
|
||||
MYSERIAL.println((unsigned char)stat, HEX);
|
||||
#endif //TMC2130_DEBUG_WR
|
||||
return stat;
|
||||
}
|
||||
|
||||
uint8_t tmc2130_rd(uint8_t cs, uint8_t addr, uint32_t* rval)
|
||||
{
|
||||
uint32_t val32 = 0;
|
||||
uint8_t stat = tmc2130_txrx(cs, addr, 0x00000000, &val32);
|
||||
if (rval != 0) *rval = val32;
|
||||
#ifdef TMC2130_DEBUG_RD
|
||||
if (!skip_debug_msg)
|
||||
{
|
||||
MYSERIAL.print("tmc2130_rd(");
|
||||
MYSERIAL.print((unsigned char)tmc2130_axis_by_cs(cs), DEC);
|
||||
MYSERIAL.print(", 0x");
|
||||
MYSERIAL.print((unsigned char)addr, HEX);
|
||||
MYSERIAL.print(", 0x");
|
||||
MYSERIAL.print((unsigned long)val32, HEX);
|
||||
MYSERIAL.print(")=0x");
|
||||
MYSERIAL.println((unsigned char)stat, HEX);
|
||||
}
|
||||
skip_debug_msg = false;
|
||||
#endif //TMC2130_DEBUG_RD
|
||||
return stat;
|
||||
}
|
||||
|
||||
uint8_t tmc2130_txrx(uint8_t cs, uint8_t addr, uint32_t wval, uint32_t* rval)
|
||||
{
|
||||
//datagram1 - request
|
||||
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
|
||||
digitalWrite(cs, LOW);
|
||||
SPI.transfer(addr); // address
|
||||
SPI.transfer((wval >> 24) & 0xff); // MSB
|
||||
SPI.transfer((wval >> 16) & 0xff);
|
||||
SPI.transfer((wval >> 8) & 0xff);
|
||||
SPI.transfer(wval & 0xff); // LSB
|
||||
digitalWrite(cs, HIGH);
|
||||
SPI.endTransaction();
|
||||
//datagram2 - response
|
||||
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
|
||||
digitalWrite(cs, LOW);
|
||||
uint8_t stat = SPI.transfer(0); // status
|
||||
uint32_t val32 = 0;
|
||||
val32 = SPI.transfer(0); // MSB
|
||||
val32 = (val32 << 8) | SPI.transfer(0);
|
||||
val32 = (val32 << 8) | SPI.transfer(0);
|
||||
val32 = (val32 << 8) | SPI.transfer(0); // LSB
|
||||
digitalWrite(cs, HIGH);
|
||||
SPI.endTransaction();
|
||||
if (rval != 0) *rval = val32;
|
||||
return stat;
|
||||
}
|
||||
|
||||
void tmc2130_eeprom_load_config()
|
||||
{
|
||||
}
|
||||
|
||||
void tmc2130_eeprom_save_config()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
#endif //TMC2130
|
97
Firmware/tmc2130.h
Normal file
97
Firmware/tmc2130.h
Normal file
|
@ -0,0 +1,97 @@
|
|||
#ifndef TMC2130_H
|
||||
#define TMC2130_H
|
||||
|
||||
extern uint8_t tmc2130_cs[4];
|
||||
|
||||
//mode
|
||||
extern uint8_t tmc2130_mode;
|
||||
//holding and running currents
|
||||
extern uint8_t tmc2130_current_h[4];
|
||||
extern uint8_t tmc2130_current_r[4];
|
||||
//flags for axis stall detection
|
||||
extern uint8_t tmc2130_axis_stalled[4];
|
||||
|
||||
extern uint8_t tmc2130_sg_thr[4];
|
||||
|
||||
extern bool tmc2130_sg_stop_on_crash;
|
||||
extern bool tmc2130_sg_crash;
|
||||
|
||||
extern uint8_t tmc2130_sg_meassure;
|
||||
extern uint16_t tmc2130_sg_meassure_cnt;
|
||||
extern uint32_t tmc2130_sg_meassure_val;
|
||||
|
||||
#define TMC2130_MODE_NORMAL 0
|
||||
#define TMC2130_MODE_SILENT 1
|
||||
|
||||
//initialize tmc2130
|
||||
extern void tmc2130_init();
|
||||
//check diag pins (called from stepper isr)
|
||||
extern void tmc2130_st_isr(uint8_t last_step_mask);
|
||||
//update stall guard (called from st_synchronize inside the loop)
|
||||
extern bool tmc2130_update_sg();
|
||||
//temperature watching (called from )
|
||||
extern void tmc2130_check_overtemp();
|
||||
//enter homing (called from homeaxis before homing starts)
|
||||
extern void tmc2130_home_enter(uint8_t axes_mask);
|
||||
//exit homing (called from homeaxis after homing ends)
|
||||
extern void tmc2130_home_exit();
|
||||
//restart homing (called from homeaxis befor move)
|
||||
extern void tmc2130_home_restart(uint8_t axis);
|
||||
|
||||
//start stallguard meassuring for single axis
|
||||
extern void tmc2130_sg_meassure_start(uint8_t axis);
|
||||
//stop current stallguard meassuring and report result
|
||||
extern uint16_t tmc2130_sg_meassure_stop();
|
||||
|
||||
|
||||
//set holding current for any axis (M911)
|
||||
extern void tmc2130_set_current_h(uint8_t axis, uint8_t current);
|
||||
//set running current for any axis (M912)
|
||||
extern void tmc2130_set_current_r(uint8_t axis, uint8_t current);
|
||||
//print currents (M913)
|
||||
extern void tmc2130_print_currents();
|
||||
|
||||
//set PWM_AMPL for any axis (M917)
|
||||
extern void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl);
|
||||
//set PWM_GRAD for any axis (M918)
|
||||
extern void tmc2130_set_pwm_grad(uint8_t axis, uint8_t pwm_ampl);
|
||||
|
||||
|
||||
extern uint16_t tmc2130_rd_MSCNT(uint8_t cs);
|
||||
|
||||
extern void tmc2130_home_pause(uint8_t axis);
|
||||
extern void tmc2130_home_resume(uint8_t axis);
|
||||
extern bool tmc2130_wait_standstill_xy(int timeout);
|
||||
|
||||
extern void tmc2130_eeprom_load_config();
|
||||
extern void tmc2130_eeprom_save_config();
|
||||
|
||||
#pragma pack(push)
|
||||
#pragma pack(1)
|
||||
struct
|
||||
{
|
||||
uint8_t mres:5; // mres - byte 0, bit 0..4 microstep resolution
|
||||
uint8_t reserved_0_0:2; // reserved - byte 0, bit 5..6
|
||||
uint8_t intpol:1; // intpol - byte 0, bit 7 linear interpolation to 255 usteps
|
||||
uint8_t pwm_ampl:8; // pwm_ampl - byte 1, bit 0..7 pwm amplitude for silent mode
|
||||
uint8_t pwm_grad:4; // pwm_grad - byte 2, bit 0..3 pwm gradient for silent mode
|
||||
uint8_t pwm_freq:2; // pwm_freq - byte 2, bit 4..5 pwm frequency for silent mode
|
||||
uint8_t reserved_2_0:2; // reserved - byte 2, bit 6..7
|
||||
uint16_t tcoolthrs:16; // tcoolthrs - byte 3..4 coolstep threshold / middle sensitivity
|
||||
int8_t sg_thrs:8; // sg_thrs - byte 5, bit 0..7 stallguard sensitivity in high power / middle sensitivity
|
||||
int8_t current_h:6; // current_h - byte 6, bit 0..5 holding current for high power mode
|
||||
uint8_t reserved_6_0:2; // reserved - byte 6, bit 6..7
|
||||
int8_t current_r:6; // current_r - byte 7, bit 0..5 running current for high power mode
|
||||
uint8_t reserved_7_0:2; // reserved - byte 7, bit 6..7
|
||||
int8_t home_sg_thrs:8; // sg_thrs - byte 8, bit 0..7 stallguard sensitivity for homing
|
||||
int8_t home_current:6; // current_r - byte 9, bit 0..5 running current for homing
|
||||
uint8_t reserved_9_0:2; // reserved - byte 9, bit 6..7
|
||||
int8_t home_dtcoolthrs:8; // dtcoolthrs - byte 10, bit 0..7 delta tcoolthrs for homing
|
||||
int8_t dtcoolthrs_low:8; // dtcoolthrs - byte 11, bit 0..7 delta tcoolthrs for low sensitivity (based on value for middle sensitivity)
|
||||
int8_t dtcoolthrs_high:8; // dtcoolthrs - byte 12, bit 0..7 delta tcoolthrs for high sensitivity (based on value for middle sensitivity)
|
||||
int8_t sg_thrs_low:8; // sg_thrs - byte 13, bit 0..7 stallguard sensitivity in high power / low sensitivity
|
||||
int8_t sg_thrs_high:8; // sg_thrs - byte 14, bit 0..7 stallguard sensitivity in high power / high sensitivity
|
||||
} tmc2130_axis_config;
|
||||
#pragma pack(pop)
|
||||
|
||||
#endif //TMC2130_H
|
File diff suppressed because it is too large
Load diff
|
@ -6,7 +6,7 @@
|
|||
|
||||
#ifdef ULTRA_LCD
|
||||
|
||||
void lcd_update();
|
||||
void lcd_update(uint8_t lcdDrawUpdateOverride = 0);
|
||||
// Call with a false parameter to suppress the LCD update from various places like the planner or the temp control.
|
||||
void lcd_update_enable(bool enable);
|
||||
void lcd_init();
|
||||
|
@ -14,6 +14,7 @@
|
|||
void lcd_setstatuspgm(const char* message);
|
||||
void lcd_setalertstatuspgm(const char* message);
|
||||
void lcd_reset_alert_level();
|
||||
uint8_t get_message_level();
|
||||
void lcd_adjust_z();
|
||||
void lcd_pick_babystep();
|
||||
void lcd_alright();
|
||||
|
@ -26,29 +27,44 @@
|
|||
void lcd_loading_color();
|
||||
void lcd_force_language_selection();
|
||||
void lcd_sdcard_stop();
|
||||
void lcd_sdcard_pause();
|
||||
void lcd_print_stop();
|
||||
void prusa_statistics(int _message);
|
||||
void lcd_confirm_print();
|
||||
|
||||
void lcd_mylang();
|
||||
bool lcd_detected(void);
|
||||
|
||||
static void lcd_selftest();
|
||||
static void lcd_selftest_v();
|
||||
static bool lcd_selftest();
|
||||
static bool lcd_selfcheck_endstops();
|
||||
|
||||
#ifdef TMC2130
|
||||
static void reset_crash_det(char axis);
|
||||
static bool lcd_selfcheck_axis_sg(char axis);
|
||||
#endif //TMC2130
|
||||
static bool lcd_selfcheck_axis(int _axis, int _travel);
|
||||
static bool lcd_selfcheck_check_heater(bool _isbed);
|
||||
static int lcd_selftest_screen(int _step, int _progress, int _progress_scale, bool _clear, int _delay);
|
||||
static void lcd_selftest_screen_step(int _row, int _col, int _state, const char *_name, const char *_indicator);
|
||||
static bool lcd_selftest_fan_dialog(int _fan);
|
||||
static void lcd_selftest_error(int _error_no, const char *_error_1, const char *_error_2);
|
||||
static void lcd_menu_statistics();
|
||||
void lcd_menu_statistics();
|
||||
static bool lcd_selfcheck_pulleys(int axis);
|
||||
|
||||
extern const char* lcd_display_message_fullscreen_P(const char *msg, uint8_t &nlines);
|
||||
inline const char* lcd_display_message_fullscreen_P(const char *msg)
|
||||
{ uint8_t nlines; return lcd_display_message_fullscreen_P(msg, nlines); }
|
||||
|
||||
extern void lcd_display_message_fullscreen_P(const char *msg);
|
||||
extern void lcd_wait_for_click();
|
||||
extern void lcd_show_fullscreen_message_and_wait_P(const char *msg);
|
||||
// 0: no, 1: yes, -1: timeouted
|
||||
extern int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true);
|
||||
|
||||
extern int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false);
|
||||
extern int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false);
|
||||
// Ask the user to move the Z axis up to the end stoppers and let
|
||||
// the user confirm that it has been done.
|
||||
extern bool lcd_calibrate_z_end_stop_manual();
|
||||
#ifndef TMC2130
|
||||
extern bool lcd_calibrate_z_end_stop_manual(bool only_z);
|
||||
#endif
|
||||
// Show the result of the calibration process on the LCD screen.
|
||||
extern void lcd_bed_calibration_show_result(BedSkewOffsetDetectionResultType result, uint8_t point_too_far_mask);
|
||||
|
||||
|
@ -67,7 +83,7 @@
|
|||
#define LCD_ALERTMESSAGERPGM(x) lcd_setalertstatuspgm((x))
|
||||
|
||||
#define LCD_UPDATE_INTERVAL 100
|
||||
#define LCD_TIMEOUT_TO_STATUS 15000
|
||||
#define LCD_TIMEOUT_TO_STATUS 30000
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
void lcd_buttons_update();
|
||||
|
@ -78,22 +94,32 @@
|
|||
#else
|
||||
FORCE_INLINE void lcd_buttons_update() {}
|
||||
#endif
|
||||
|
||||
|
||||
// To be used in lcd_commands_type.
|
||||
#define LCD_COMMAND_IDLE 0
|
||||
#define LCD_COMMAND_LOAD_FILAMENT 1
|
||||
#define LCD_COMMAND_STOP_PRINT 2
|
||||
#define LCD_COMMAND_FARM_MODE_CONFIRM 4
|
||||
#define LCD_COMMAND_LONG_PAUSE 5
|
||||
#define LCD_COMMAND_LONG_PAUSE_RESUME 6
|
||||
#define LCD_COMMAND_PID_EXTRUDER 7
|
||||
#define LCD_COMMAND_V2_CAL 8
|
||||
|
||||
extern unsigned long lcd_timeoutToStatus;
|
||||
extern int lcd_commands_type;
|
||||
|
||||
extern int plaPreheatHotendTemp;
|
||||
extern int plaPreheatHPBTemp;
|
||||
extern int plaPreheatFanSpeed;
|
||||
|
||||
extern int absPreheatHotendTemp;
|
||||
extern int absPreheatHPBTemp;
|
||||
extern int absPreheatFanSpeed;
|
||||
|
||||
extern bool farm_mode;
|
||||
extern uint8_t farm_mode;
|
||||
extern int farm_no;
|
||||
extern int farm_timer;
|
||||
extern int farm_status;
|
||||
|
||||
#ifdef SNMM
|
||||
extern uint8_t snmm_extruder;
|
||||
#endif // SNMM
|
||||
|
||||
extern bool cancel_heatup;
|
||||
extern bool isPrintPaused;
|
||||
|
||||
#ifdef FILAMENT_LCD_DISPLAY
|
||||
extern unsigned long message_millis;
|
||||
|
@ -191,4 +217,62 @@ extern void lcd_implementation_print_at(uint8_t x, uint8_t y, int i);
|
|||
extern void lcd_implementation_print(float f);
|
||||
extern void lcd_implementation_print_at(uint8_t x, uint8_t y, const char *str);
|
||||
|
||||
#endif //ULTRALCD_H
|
||||
|
||||
void change_extr(int extr);
|
||||
static void lcd_colorprint_change();
|
||||
static int get_ext_nr();
|
||||
static void extr_adj(int extruder);
|
||||
static void extr_adj_0();
|
||||
static void extr_adj_1();
|
||||
static void extr_adj_2();
|
||||
static void extr_adj_3();
|
||||
static void fil_load_menu();
|
||||
static void fil_unload_menu();
|
||||
static void extr_unload_0();
|
||||
static void extr_unload_1();
|
||||
static void extr_unload_2();
|
||||
static void extr_unload_3();
|
||||
static void lcd_disable_farm_mode();
|
||||
static void lcd_set_fan_check();
|
||||
void extr_unload_all();
|
||||
void extr_unload_used();
|
||||
void extr_unload();
|
||||
static char snmm_stop_print_menu();
|
||||
static float count_e(float layer_heigth, float extrusion_width, float extrusion_length);
|
||||
static void lcd_babystep_z();
|
||||
|
||||
void stack_error();
|
||||
static void lcd_ping_allert();
|
||||
void lcd_printer_connected();
|
||||
void lcd_ping();
|
||||
|
||||
void lcd_calibrate_extruder();
|
||||
void lcd_farm_sdcard_menu();
|
||||
|
||||
//void getFileDescription(char *name, char *description);
|
||||
|
||||
void lcd_farm_sdcard_menu_w();
|
||||
//void get_description();
|
||||
|
||||
//void lcd_wait_for_cool_down();
|
||||
void adjust_bed_reset();
|
||||
void lcd_extr_cal_reset();
|
||||
|
||||
union MenuData;
|
||||
|
||||
void bowden_menu();
|
||||
char reset_menu();
|
||||
char choose_extruder_menu();
|
||||
|
||||
void lcd_pinda_calibration_menu();
|
||||
void lcd_calibrate_pinda();
|
||||
void lcd_temp_calibration_set();
|
||||
|
||||
void display_loading();
|
||||
|
||||
void lcd_service_mode_show_result();
|
||||
|
||||
void lcd_wizard();
|
||||
void lcd_wizard(int state);
|
||||
|
||||
#endif //ULTRALCD_H
|
|
@ -461,6 +461,35 @@ void lcd_set_custom_characters_arrows()
|
|||
|
||||
lcd.createChar(1, arrdown);
|
||||
}
|
||||
|
||||
void lcd_set_custom_characters_nextpage()
|
||||
{
|
||||
|
||||
byte arrdown[8] = {
|
||||
B00000,
|
||||
B00000,
|
||||
B10001,
|
||||
B01010,
|
||||
B00100,
|
||||
B10001,
|
||||
B01010,
|
||||
B00100
|
||||
};
|
||||
|
||||
byte confirm[8] = {
|
||||
B00000,
|
||||
B00001,
|
||||
B00011,
|
||||
B10110,
|
||||
B11100,
|
||||
B01000,
|
||||
B00000
|
||||
};
|
||||
|
||||
lcd.createChar(1, arrdown);
|
||||
lcd.createChar(2, confirm);
|
||||
}
|
||||
|
||||
void lcd_set_custom_characters_degree()
|
||||
{
|
||||
byte degree[8] = {
|
||||
|
@ -655,13 +684,24 @@ static void lcd_implementation_status_screen()
|
|||
lcd.print('/');
|
||||
lcd.print(itostr3left(tTarget));
|
||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
|
||||
//Print the Z coordinates
|
||||
lcd.setCursor(LCD_WIDTH - 8-2, 0);
|
||||
lcd.print(" Z");
|
||||
lcd.print(ftostr32sp(current_position[Z_AXIS] + 0.00001));
|
||||
#if 1
|
||||
lcd_printPGM(PSTR(" Z"));
|
||||
if (custom_message_type == 1) {
|
||||
// In a bed calibration mode.
|
||||
lcd_printPGM(PSTR(" --- "));
|
||||
} else {
|
||||
lcd.print(ftostr32sp(current_position[Z_AXIS] + 0.00001));
|
||||
lcd.print(' ');
|
||||
}
|
||||
#else
|
||||
lcd_printPGM(PSTR(" Queue:"));
|
||||
lcd.print(int(moves_planned()));
|
||||
lcd.print(' ');
|
||||
#endif
|
||||
|
||||
//Print the Bedtemperature
|
||||
lcd.setCursor(0, 1);
|
||||
|
@ -672,18 +712,56 @@ static void lcd_implementation_status_screen()
|
|||
lcd.print('/');
|
||||
lcd.print(itostr3left(tTarget));
|
||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
|
||||
#if 1
|
||||
//Print Feedrate
|
||||
lcd.setCursor(LCD_WIDTH - 8-2, 1);
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
lcd.print(LCD_STR_FEEDRATE[0]);
|
||||
lcd.print(itostr3(feedmultiply));
|
||||
lcd.print('%');
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR("% "));
|
||||
|
||||
//lcd.setCursor(8, 0);
|
||||
//lcd.print(itostr3(fan_speed[0]));
|
||||
//lcd.setCursor(8, 1);
|
||||
//lcd.print(itostr3(fan_speed[1]));
|
||||
|
||||
#else
|
||||
//Print Feedrate
|
||||
lcd.setCursor(LCD_WIDTH - 8-2, 1);
|
||||
lcd.print(LCD_STR_FEEDRATE[0]);
|
||||
lcd.print(itostr3(feedmultiply));
|
||||
lcd_printPGM(PSTR("% Q"));
|
||||
{
|
||||
uint8_t queue = planner_queue_min();
|
||||
if (queue < (BLOCK_BUFFER_SIZE >> 1)) {
|
||||
lcd.print('!');
|
||||
} else {
|
||||
lcd.print((char)(queue / 10) + '0');
|
||||
queue %= 10;
|
||||
}
|
||||
lcd.print((char)queue + '0');
|
||||
planner_queue_min_reset();
|
||||
}
|
||||
#endif
|
||||
bool print_sd_status = true;
|
||||
|
||||
#ifdef PINDA_THERMISTOR
|
||||
// if (farm_mode && (custom_message_type == 4))
|
||||
if (false)
|
||||
{
|
||||
lcd.setCursor(0, 2);
|
||||
lcd_printPGM(PSTR("P"));
|
||||
lcd.print(ftostr3(current_temperature_pinda));
|
||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||
print_sd_status = false;
|
||||
}
|
||||
#endif //PINDA_THERMISTOR
|
||||
|
||||
|
||||
if (print_sd_status)
|
||||
{
|
||||
//Print SD status
|
||||
lcd.setCursor(0, 2);
|
||||
if (is_usb_printing)
|
||||
|
@ -711,41 +789,72 @@ static void lcd_implementation_status_screen()
|
|||
lcd.print('%');
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Farm number display
|
||||
if (farm_mode)
|
||||
{
|
||||
lcd.print(" F");
|
||||
lcd_printPGM(PSTR(" F"));
|
||||
lcd.print(farm_no);
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
|
||||
// Beat display
|
||||
lcd.setCursor(LCD_WIDTH - 1, 0);
|
||||
if ( (millis() - kicktime) < 60000 ) {
|
||||
|
||||
lcd_printPGM(PSTR("L"));
|
||||
|
||||
}else{
|
||||
lcd_printPGM(PSTR(" "));
|
||||
}
|
||||
|
||||
}
|
||||
else {
|
||||
#ifdef SNMM
|
||||
lcd_printPGM(PSTR(" E"));
|
||||
lcd.print(get_ext_nr() + 1);
|
||||
|
||||
#else
|
||||
lcd.setCursor(LCD_WIDTH - 8 - 2, 2);
|
||||
lcd_printPGM(PSTR(" "));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
||||
//Print time elapsed
|
||||
lcd.setCursor(LCD_WIDTH - 8 -2, 2);
|
||||
lcd.print(" ");
|
||||
lcd.setCursor(LCD_WIDTH - 8 -1, 2);
|
||||
lcd_printPGM(PSTR(" "));
|
||||
lcd.print(LCD_STR_CLOCK[0]);
|
||||
if(starttime != 0)
|
||||
{
|
||||
uint16_t time = millis()/60000 - starttime/60000;
|
||||
uint16_t time = millis() / 60000 - starttime / 60000;
|
||||
lcd.print(itostr2(time/60));
|
||||
lcd.print(':');
|
||||
lcd.print(itostr2(time%60));
|
||||
}else{
|
||||
lcd_printPGM(PSTR("--:--"));
|
||||
}
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
|
||||
#ifdef DEBUG_DISABLE_LCD_STATUS_LINE
|
||||
return;
|
||||
#endif //DEBUG_DISABLE_LCD_STATUS_LINE
|
||||
|
||||
//Print status line
|
||||
lcd.setCursor(0, 3);
|
||||
|
||||
// If heating in progress, set flag
|
||||
if (heating_status != 0) { custom_message = true; }
|
||||
|
||||
// If printing from SD, show what we are printing
|
||||
if ((IS_SD_PRINTING) && !custom_message)
|
||||
{
|
||||
|
||||
if(strcmp(longFilenameOLD, card.longFilename) != 0)
|
||||
{
|
||||
memset(longFilenameOLD,'\0',strlen(longFilenameOLD));
|
||||
sprintf(longFilenameOLD, "%s", card.longFilename);
|
||||
sprintf_P(longFilenameOLD, PSTR("%s"), card.longFilename);
|
||||
scrollstuff = 0;
|
||||
}
|
||||
|
||||
|
@ -783,10 +892,13 @@ static void lcd_implementation_status_screen()
|
|||
|
||||
|
||||
}
|
||||
// If not, check for other special events
|
||||
else
|
||||
{
|
||||
|
||||
if (custom_message)
|
||||
{
|
||||
// If heating flag, show progress of heating.
|
||||
if (heating_status != 0)
|
||||
{
|
||||
heating_status_counter++;
|
||||
|
@ -800,7 +912,7 @@ static void lcd_implementation_status_screen()
|
|||
for (int dots = 0; dots < heating_status_counter; dots++)
|
||||
{
|
||||
lcd.setCursor(7 + dots, 3);
|
||||
lcd_printPGM(PSTR("."));
|
||||
lcd.print('.');
|
||||
}
|
||||
|
||||
switch (heating_status)
|
||||
|
@ -831,16 +943,18 @@ static void lcd_implementation_status_screen()
|
|||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (custom_message_type == 1) //// Z calibration G80 mesh bed leveling
|
||||
|
||||
// If mesh bed leveling in progress, show the status
|
||||
|
||||
if (custom_message_type == 1)
|
||||
{
|
||||
if (custom_message_state > 10)
|
||||
{
|
||||
lcd.setCursor(0, 3);
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_HOMEYZ_PROGRESS);
|
||||
lcd.print(" : ");
|
||||
lcd_printPGM(PSTR(" : "));
|
||||
lcd.print(custom_message_state-10);
|
||||
}
|
||||
else
|
||||
|
@ -852,34 +966,64 @@ static void lcd_implementation_status_screen()
|
|||
custom_message = false;
|
||||
custom_message_type = 0;
|
||||
}
|
||||
if (custom_message_state > 3 && custom_message_state < 10 )
|
||||
if (custom_message_state > 3 && custom_message_state <= 10 )
|
||||
{
|
||||
lcd.setCursor(0, 3);
|
||||
lcd.print(" ");
|
||||
lcd_printPGM(PSTR(" "));
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_HOMEYZ_DONE);
|
||||
custom_message_state--;
|
||||
}
|
||||
if (custom_message_state == 10)
|
||||
{
|
||||
lcd_printPGM(MSG_HOMEYZ_DONE);
|
||||
custom_message_state = 9;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (custom_message_type == 2) //// load filament
|
||||
// If loading filament, print status
|
||||
if (custom_message_type == 2)
|
||||
{
|
||||
lcd.print(lcd_status_message);
|
||||
}
|
||||
// PID tuning in progress
|
||||
if (custom_message_type == 3) {
|
||||
lcd.print(lcd_status_message);
|
||||
if (pid_cycle <= pid_number_of_cycles && custom_message_state > 0) {
|
||||
lcd.setCursor(10, 3);
|
||||
lcd.print(itostr3(pid_cycle));
|
||||
|
||||
lcd.print('/');
|
||||
lcd.print(itostr3left(pid_number_of_cycles));
|
||||
}
|
||||
}
|
||||
// PINDA temp calibration in progress
|
||||
if (custom_message_type == 4) {
|
||||
char progress[4];
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_TEMP_CALIBRATION);
|
||||
lcd.setCursor(12, 3);
|
||||
sprintf(progress, "%d/6", custom_message_state);
|
||||
lcd.print(progress);
|
||||
}
|
||||
// temp compensation preheat
|
||||
if (custom_message_type == 5) {
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_PINDA_PREHEAT);
|
||||
if (custom_message_state <= PINDA_HEAT_T) {
|
||||
lcd_printPGM(PSTR(": "));
|
||||
lcd.print(custom_message_state); //seconds
|
||||
lcd.print(' ');
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
// Nothing special, print status message normally
|
||||
lcd.print(lcd_status_message);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Fill the rest of line to have nice and clean output
|
||||
for(int fillspace = 0; fillspace<20;fillspace++)
|
||||
{
|
||||
if((lcd_status_message[fillspace] > 31 ))
|
||||
|
@ -1061,21 +1205,12 @@ static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char*
|
|||
|
||||
lcd.setCursor(0, row);
|
||||
lcd.print('>');
|
||||
if (longFilename[0] != '\0')
|
||||
{
|
||||
|
||||
filename = longFilename;
|
||||
//longFilename[LCD_WIDTH-1] = '\0';
|
||||
}
|
||||
|
||||
int i = 1;
|
||||
int j = 0;
|
||||
int inter = 0;
|
||||
char* longFilenameTMP = longFilename;
|
||||
|
||||
while( ((c = *longFilenameTMP) != '\0') && (inter == 0) )
|
||||
while((c = *longFilenameTMP) != '\0')
|
||||
{
|
||||
|
||||
lcd.setCursor(i, row);
|
||||
lcd.print(c);
|
||||
i++;
|
||||
|
@ -1083,20 +1218,23 @@ static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char*
|
|||
if(i==LCD_WIDTH){
|
||||
i=1;
|
||||
j++;
|
||||
longFilenameTMP = longFilename;
|
||||
longFilenameTMP = longFilenameTMP+j;
|
||||
longFilenameTMP = longFilename + j;
|
||||
n = LCD_WIDTH - 1;
|
||||
for(int g = 0; ((g<300)&&(inter == 0)) ;g++){
|
||||
for(int g = 0; g<300 ;g++){
|
||||
manage_heater();
|
||||
if(LCD_CLICKED || ( enc_dif != encoderDiff )){
|
||||
|
||||
// inter = 1;
|
||||
longFilenameTMP = longFilename;
|
||||
*(longFilenameTMP + LCD_WIDTH - 2) = '\0';
|
||||
i = 1;
|
||||
j = 0;
|
||||
break;
|
||||
}else{
|
||||
delay(1);
|
||||
if (j == 1) delay(3); //wait around 1.2 s to start scrolling text
|
||||
delay(1); //then scroll with redrawing every 300 ms
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
if(c!='\0'){
|
||||
lcd.setCursor(i, row);
|
||||
|
|
31
Firmware/uni_avr_rpi.h
Normal file
31
Firmware/uni_avr_rpi.h
Normal file
|
@ -0,0 +1,31 @@
|
|||
// unification for AVR and RPI
|
||||
#define __AVR
|
||||
|
||||
#ifdef __AVR
|
||||
//#include "Arduino.h"
|
||||
#include "Marlin.h"
|
||||
#define GPIO_INP(gpio) pinMode(gpio, INPUT)
|
||||
#define GPIO_OUT(gpio) pinMode(gpio, OUTPUT)
|
||||
#define GPIO_SET(gpio) digitalWrite(gpio, HIGH)
|
||||
#define GPIO_CLR(gpio) digitalWrite(gpio, LOW)
|
||||
#define GPIO_GET(gpio) (digitalRead(gpio) != LOW)
|
||||
#define DELAY(delay) delayMicroseconds(delay)
|
||||
#define PRINT MYSERIAL.print
|
||||
#endif //RC522_AVR
|
||||
|
||||
#ifdef __RPI
|
||||
#include <bcm2835.h>
|
||||
#define GPIO_INP(gpio) bcm2835_gpio_fsel(gpio, BCM2835_GPIO_FSEL_INPT)
|
||||
#define GPIO_OUT(gpio) bcm2835_gpio_fsel(gpio, BCM2835_GPIO_FSEL_OUTP)
|
||||
#define GPIO_SET(gpio) bcm2835_gpio_write(gpio, HIGH)
|
||||
#define GPIO_CLR(gpio) bcm2835_gpio_write(gpio, LOW)
|
||||
#define GPIO_GET(gpio) (bcm2835_gpio_lev(gpio) != LOW)
|
||||
#include <unistd.h>
|
||||
#define DELAY(delay) usleep(delay)
|
||||
#define PRINT(p) print(p)
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
void print(const char* pc) { printf("%s", pc); }
|
||||
void print(int v) { printf("%d", v); }
|
||||
void print(float v) { printf("%f", v); }
|
||||
#endif //RC522_RPI
|
|
@ -1,288 +1,288 @@
|
|||
#include "Configuration.h"
|
||||
|
||||
#include "ultralcd.h"
|
||||
#include "language.h"
|
||||
#include "util.h"
|
||||
|
||||
// Allocate the version string in the program memory. Otherwise the string lands either on the stack or in the global RAM.
|
||||
const char FW_VERSION_STR[] PROGMEM = FW_version;
|
||||
|
||||
const char* FW_VERSION_STR_P()
|
||||
{
|
||||
return FW_VERSION_STR;
|
||||
}
|
||||
|
||||
const char FW_PRUSA3D_MAGIC_STR[] PROGMEM = FW_PRUSA3D_MAGIC;
|
||||
|
||||
const char* FW_PRUSA3D_MAGIC_STR_P()
|
||||
{
|
||||
return FW_PRUSA3D_MAGIC_STR;
|
||||
}
|
||||
|
||||
const char STR_REVISION_DEV [] PROGMEM = "dev";
|
||||
const char STR_REVISION_ALPHA[] PROGMEM = "alpha";
|
||||
const char STR_REVISION_BETA [] PROGMEM = "beta";
|
||||
const char STR_REVISION_RC [] PROGMEM = "rc";
|
||||
|
||||
inline bool is_whitespace_or_nl(char c)
|
||||
{
|
||||
return c == ' ' || c == '\t' || c == '\n' || c == 'r';
|
||||
}
|
||||
|
||||
inline bool is_whitespace_or_nl_or_eol(char c)
|
||||
{
|
||||
return c == 0 || c == ' ' || c == '\t' || c == '\n' || c == '\r';
|
||||
}
|
||||
|
||||
inline bool is_digit(char c)
|
||||
{
|
||||
return c >= '0' && c <= '9';
|
||||
}
|
||||
|
||||
// Parse a major.minor.revision version number.
|
||||
// Return true if valid.
|
||||
inline bool parse_version(const char *str, uint16_t version[4])
|
||||
{
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Parsing version string ");
|
||||
SERIAL_ECHO(str);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
|
||||
const char *major = str;
|
||||
const char *p = str;
|
||||
while (is_digit(*p)) ++ p;
|
||||
if (*p != '.')
|
||||
return false;
|
||||
const char *minor = ++ p;
|
||||
while (is_digit(*p)) ++ p;
|
||||
if (*p != '.')
|
||||
return false;
|
||||
const char *rev = ++ p;
|
||||
while (is_digit(*p)) ++ p;
|
||||
if (! is_whitespace_or_nl_or_eol(*p) && *p != '-')
|
||||
return false;
|
||||
|
||||
char *endptr = NULL;
|
||||
version[0] = strtol(major, &endptr, 10);
|
||||
if (endptr != minor - 1)
|
||||
return false;
|
||||
version[1] = strtol(minor, &endptr, 10);
|
||||
if (endptr != rev - 1)
|
||||
return false;
|
||||
version[2] = strtol(rev, &endptr, 10);
|
||||
if (endptr != p)
|
||||
return false;
|
||||
|
||||
version[3] = FIRMWARE_REVISION_RELEASED;
|
||||
if (*p ++ == '-') {
|
||||
const char *q = p;
|
||||
while (! is_whitespace_or_nl_or_eol(*q))
|
||||
++ q;
|
||||
uint8_t n = q - p;
|
||||
if (n == strlen_P(STR_REVISION_DEV) && strncmp_P(p, STR_REVISION_DEV, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_DEV;
|
||||
else if (n == strlen_P(STR_REVISION_ALPHA) && strncmp_P(p, STR_REVISION_ALPHA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_ALPHA;
|
||||
else if (n == strlen_P(STR_REVISION_BETA) && strncmp_P(p, STR_REVISION_BETA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_BETA;
|
||||
else if ((n == 2 || n == 3) && p[0] == 'r' && p[1] == 'c') {
|
||||
if (n == 2)
|
||||
version[3] = FIRMWARE_REVISION_RC;
|
||||
else {
|
||||
if (is_digit(p[2]))
|
||||
version[3] = FIRMWARE_REVISION_RC + p[2] - '1';
|
||||
else
|
||||
return false;
|
||||
}
|
||||
} else
|
||||
return false;
|
||||
}
|
||||
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Version parsed, major: ");
|
||||
SERIAL_ECHO(version[0]);
|
||||
SERIAL_ECHOPGM(", minor: ");
|
||||
SERIAL_ECHO(version[1]);
|
||||
SERIAL_ECHOPGM(", revision: ");
|
||||
SERIAL_ECHO(version[2]);
|
||||
SERIAL_ECHOPGM(", flavor: ");
|
||||
SERIAL_ECHO(version[3]);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
inline bool strncmp_PP(const char *p1, const char *p2, uint8_t n)
|
||||
{
|
||||
for (; n > 0; -- n, ++ p1, ++ p2) {
|
||||
if (pgm_read_byte(p1) < pgm_read_byte(p2))
|
||||
return -1;
|
||||
if (pgm_read_byte(p1) > pgm_read_byte(p2))
|
||||
return 1;
|
||||
if (pgm_read_byte(p1) == 0)
|
||||
return 0;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Parse a major.minor.revision version number.
|
||||
// Return true if valid.
|
||||
inline bool parse_version_P(const char *str, uint16_t version[4])
|
||||
{
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Parsing version string ");
|
||||
SERIAL_ECHORPGM(str);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
|
||||
const char *major = str;
|
||||
const char *p = str;
|
||||
while (is_digit(char(pgm_read_byte(p)))) ++ p;
|
||||
if (pgm_read_byte(p) != '.')
|
||||
return false;
|
||||
const char *minor = ++ p;
|
||||
while (is_digit(char(pgm_read_byte(p)))) ++ p;
|
||||
if (pgm_read_byte(p) != '.')
|
||||
return false;
|
||||
const char *rev = ++ p;
|
||||
while (is_digit(char(pgm_read_byte(p)))) ++ p;
|
||||
if (! is_whitespace_or_nl_or_eol(char(pgm_read_byte(p))) && pgm_read_byte(p) != '-')
|
||||
return false;
|
||||
|
||||
char buf[5];
|
||||
uint8_t n = minor - major - 1;
|
||||
if (n > 4)
|
||||
return false;
|
||||
memcpy_P(buf, major, n); buf[n] = 0;
|
||||
char *endptr = NULL;
|
||||
version[0] = strtol(buf, &endptr, 10);
|
||||
if (*endptr != 0)
|
||||
return false;
|
||||
n = rev - minor - 1;
|
||||
if (n > 4)
|
||||
return false;
|
||||
memcpy_P(buf, minor, n); buf[n] = 0;
|
||||
version[1] = strtol(buf, &endptr, 10);
|
||||
if (*endptr != 0)
|
||||
return false;
|
||||
n = p - rev;
|
||||
if (n > 4)
|
||||
return false;
|
||||
memcpy_P(buf, rev, n);
|
||||
buf[n] = 0;
|
||||
version[2] = strtol(buf, &endptr, 10);
|
||||
if (*endptr != 0)
|
||||
return false;
|
||||
|
||||
version[3] = FIRMWARE_REVISION_RELEASED;
|
||||
if (pgm_read_byte(p ++) == '-') {
|
||||
const char *q = p;
|
||||
while (! is_whitespace_or_nl_or_eol(char(pgm_read_byte(q))))
|
||||
++ q;
|
||||
n = q - p;
|
||||
if (n == strlen_P(STR_REVISION_DEV) && strncmp_PP(p, STR_REVISION_DEV, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_DEV;
|
||||
else if (n == strlen_P(STR_REVISION_ALPHA) && strncmp_PP(p, STR_REVISION_ALPHA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_ALPHA;
|
||||
else if (n == strlen_P(STR_REVISION_BETA) && strncmp_PP(p, STR_REVISION_BETA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_BETA;
|
||||
else if ((n == 2 || n == 3) && strncmp_PP(p, STR_REVISION_RC, 2) == 0) {
|
||||
if (n == 2)
|
||||
version[3] = FIRMWARE_REVISION_RC;
|
||||
else {
|
||||
p += 2;
|
||||
if (is_digit(pgm_read_byte(p)))
|
||||
version[3] = FIRMWARE_REVISION_RC + pgm_read_byte(p) - '1';
|
||||
else
|
||||
return false;
|
||||
}
|
||||
} else
|
||||
return false;
|
||||
}
|
||||
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Version parsed, major: ");
|
||||
SERIAL_ECHO(version[0]);
|
||||
SERIAL_ECHOPGM(", minor: ");
|
||||
SERIAL_ECHO(version[1]);
|
||||
SERIAL_ECHOPGM(", revision: ");
|
||||
SERIAL_ECHO(version[2]);
|
||||
SERIAL_ECHOPGM(", flavor: ");
|
||||
SERIAL_ECHO(version[3]);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
// 1 - yes, 0 - false, -1 - error;
|
||||
inline int8_t is_provided_version_newer(const char *version_string)
|
||||
{
|
||||
uint16_t ver_gcode[3], ver_current[3];
|
||||
if (! parse_version(version_string, ver_gcode))
|
||||
return -1;
|
||||
if (! parse_version_P(FW_VERSION_STR, ver_current))
|
||||
return 0; // this shall not happen
|
||||
for (uint8_t i = 0; i < 3; ++ i)
|
||||
if (ver_gcode[i] > ver_current[i])
|
||||
return 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool show_upgrade_dialog_if_version_newer(const char *version_string)
|
||||
{
|
||||
uint16_t ver_gcode[4], ver_current[4];
|
||||
if (! parse_version(version_string, ver_gcode)) {
|
||||
// SERIAL_PROTOCOLLNPGM("parse_version failed");
|
||||
return false;
|
||||
}
|
||||
if (! parse_version_P(FW_VERSION_STR, ver_current)) {
|
||||
// SERIAL_PROTOCOLLNPGM("parse_version_P failed");
|
||||
return false; // this shall not happen
|
||||
}
|
||||
// SERIAL_PROTOCOLLNPGM("versions parsed");
|
||||
bool upgrade = false;
|
||||
for (uint8_t i = 0; i < 4; ++ i) {
|
||||
if (ver_gcode[i] > ver_current[i]) {
|
||||
upgrade = true;
|
||||
break;
|
||||
} else if (ver_gcode[i] < ver_current[i])
|
||||
break;
|
||||
}
|
||||
|
||||
if (upgrade) {
|
||||
lcd_display_message_fullscreen_P(MSG_NEW_FIRMWARE_AVAILABLE);
|
||||
lcd_print_at_PGM(0, 2, PSTR(""));
|
||||
for (const char *c = version_string; ! is_whitespace_or_nl_or_eol(*c); ++ c)
|
||||
lcd_implementation_write(*c);
|
||||
lcd_print_at_PGM(0, 3, MSG_NEW_FIRMWARE_PLEASE_UPGRADE);
|
||||
tone(BEEPER, 1000);
|
||||
delay_keep_alive(50);
|
||||
noTone(BEEPER);
|
||||
delay_keep_alive(500);
|
||||
tone(BEEPER, 1000);
|
||||
delay_keep_alive(50);
|
||||
noTone(BEEPER);
|
||||
lcd_wait_for_click();
|
||||
lcd_update_enable(true);
|
||||
lcd_implementation_clear();
|
||||
lcd_update();
|
||||
}
|
||||
|
||||
// Succeeded.
|
||||
return true;
|
||||
}
|
||||
|
||||
void update_current_firmware_version_to_eeprom()
|
||||
{
|
||||
for (int8_t i = 0; i < FW_PRUSA3D_MAGIC_LEN; ++ i)
|
||||
eeprom_update_byte((uint8_t*)(EEPROM_FIRMWARE_PRUSA_MAGIC+i), pgm_read_byte(FW_PRUSA3D_MAGIC_STR+i));
|
||||
uint16_t ver_current[4];
|
||||
if (parse_version_P(FW_VERSION_STR, ver_current)) {
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_MAJOR, ver_current[0]);
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_MINOR, ver_current[1]);
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_REVISION, ver_current[2]);
|
||||
// See FirmwareRevisionFlavorType for the definition of firmware flavors.
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_FLAVOR, ver_current[3]);
|
||||
}
|
||||
}
|
||||
#include "Configuration.h"
|
||||
|
||||
#include "ultralcd.h"
|
||||
#include "language.h"
|
||||
#include "util.h"
|
||||
|
||||
// Allocate the version string in the program memory. Otherwise the string lands either on the stack or in the global RAM.
|
||||
const char FW_VERSION_STR[] PROGMEM = FW_version;
|
||||
|
||||
const char* FW_VERSION_STR_P()
|
||||
{
|
||||
return FW_VERSION_STR;
|
||||
}
|
||||
|
||||
const char FW_PRUSA3D_MAGIC_STR[] PROGMEM = FW_PRUSA3D_MAGIC;
|
||||
|
||||
const char* FW_PRUSA3D_MAGIC_STR_P()
|
||||
{
|
||||
return FW_PRUSA3D_MAGIC_STR;
|
||||
}
|
||||
|
||||
const char STR_REVISION_DEV [] PROGMEM = "dev";
|
||||
const char STR_REVISION_ALPHA[] PROGMEM = "alpha";
|
||||
const char STR_REVISION_BETA [] PROGMEM = "beta";
|
||||
const char STR_REVISION_RC [] PROGMEM = "rc";
|
||||
|
||||
inline bool is_whitespace_or_nl(char c)
|
||||
{
|
||||
return c == ' ' || c == '\t' || c == '\n' || c == 'r';
|
||||
}
|
||||
|
||||
inline bool is_whitespace_or_nl_or_eol(char c)
|
||||
{
|
||||
return c == 0 || c == ' ' || c == '\t' || c == '\n' || c == '\r';
|
||||
}
|
||||
|
||||
inline bool is_digit(char c)
|
||||
{
|
||||
return c >= '0' && c <= '9';
|
||||
}
|
||||
|
||||
// Parse a major.minor.revision version number.
|
||||
// Return true if valid.
|
||||
inline bool parse_version(const char *str, uint16_t version[4])
|
||||
{
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Parsing version string ");
|
||||
SERIAL_ECHO(str);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
|
||||
const char *major = str;
|
||||
const char *p = str;
|
||||
while (is_digit(*p)) ++ p;
|
||||
if (*p != '.')
|
||||
return false;
|
||||
const char *minor = ++ p;
|
||||
while (is_digit(*p)) ++ p;
|
||||
if (*p != '.')
|
||||
return false;
|
||||
const char *rev = ++ p;
|
||||
while (is_digit(*p)) ++ p;
|
||||
if (! is_whitespace_or_nl_or_eol(*p) && *p != '-')
|
||||
return false;
|
||||
|
||||
char *endptr = NULL;
|
||||
version[0] = strtol(major, &endptr, 10);
|
||||
if (endptr != minor - 1)
|
||||
return false;
|
||||
version[1] = strtol(minor, &endptr, 10);
|
||||
if (endptr != rev - 1)
|
||||
return false;
|
||||
version[2] = strtol(rev, &endptr, 10);
|
||||
if (endptr != p)
|
||||
return false;
|
||||
|
||||
version[3] = FIRMWARE_REVISION_RELEASED;
|
||||
if (*p ++ == '-') {
|
||||
const char *q = p;
|
||||
while (! is_whitespace_or_nl_or_eol(*q))
|
||||
++ q;
|
||||
uint8_t n = q - p;
|
||||
if (n == strlen_P(STR_REVISION_DEV) && strncmp_P(p, STR_REVISION_DEV, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_DEV;
|
||||
else if (n == strlen_P(STR_REVISION_ALPHA) && strncmp_P(p, STR_REVISION_ALPHA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_ALPHA;
|
||||
else if (n == strlen_P(STR_REVISION_BETA) && strncmp_P(p, STR_REVISION_BETA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_BETA;
|
||||
else if ((n == 2 || n == 3) && p[0] == 'r' && p[1] == 'c') {
|
||||
if (n == 2)
|
||||
version[3] = FIRMWARE_REVISION_RC;
|
||||
else {
|
||||
if (is_digit(p[2]))
|
||||
version[3] = FIRMWARE_REVISION_RC + p[2] - '1';
|
||||
else
|
||||
return false;
|
||||
}
|
||||
} else
|
||||
return false;
|
||||
}
|
||||
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Version parsed, major: ");
|
||||
SERIAL_ECHO(version[0]);
|
||||
SERIAL_ECHOPGM(", minor: ");
|
||||
SERIAL_ECHO(version[1]);
|
||||
SERIAL_ECHOPGM(", revision: ");
|
||||
SERIAL_ECHO(version[2]);
|
||||
SERIAL_ECHOPGM(", flavor: ");
|
||||
SERIAL_ECHO(version[3]);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
inline bool strncmp_PP(const char *p1, const char *p2, uint8_t n)
|
||||
{
|
||||
for (; n > 0; -- n, ++ p1, ++ p2) {
|
||||
if (pgm_read_byte(p1) < pgm_read_byte(p2))
|
||||
return -1;
|
||||
if (pgm_read_byte(p1) > pgm_read_byte(p2))
|
||||
return 1;
|
||||
if (pgm_read_byte(p1) == 0)
|
||||
return 0;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Parse a major.minor.revision version number.
|
||||
// Return true if valid.
|
||||
inline bool parse_version_P(const char *str, uint16_t version[4])
|
||||
{
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Parsing version string ");
|
||||
SERIAL_ECHORPGM(str);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
|
||||
const char *major = str;
|
||||
const char *p = str;
|
||||
while (is_digit(char(pgm_read_byte(p)))) ++ p;
|
||||
if (pgm_read_byte(p) != '.')
|
||||
return false;
|
||||
const char *minor = ++ p;
|
||||
while (is_digit(char(pgm_read_byte(p)))) ++ p;
|
||||
if (pgm_read_byte(p) != '.')
|
||||
return false;
|
||||
const char *rev = ++ p;
|
||||
while (is_digit(char(pgm_read_byte(p)))) ++ p;
|
||||
if (! is_whitespace_or_nl_or_eol(char(pgm_read_byte(p))) && pgm_read_byte(p) != '-')
|
||||
return false;
|
||||
|
||||
char buf[5];
|
||||
uint8_t n = minor - major - 1;
|
||||
if (n > 4)
|
||||
return false;
|
||||
memcpy_P(buf, major, n); buf[n] = 0;
|
||||
char *endptr = NULL;
|
||||
version[0] = strtol(buf, &endptr, 10);
|
||||
if (*endptr != 0)
|
||||
return false;
|
||||
n = rev - minor - 1;
|
||||
if (n > 4)
|
||||
return false;
|
||||
memcpy_P(buf, minor, n); buf[n] = 0;
|
||||
version[1] = strtol(buf, &endptr, 10);
|
||||
if (*endptr != 0)
|
||||
return false;
|
||||
n = p - rev;
|
||||
if (n > 4)
|
||||
return false;
|
||||
memcpy_P(buf, rev, n);
|
||||
buf[n] = 0;
|
||||
version[2] = strtol(buf, &endptr, 10);
|
||||
if (*endptr != 0)
|
||||
return false;
|
||||
|
||||
version[3] = FIRMWARE_REVISION_RELEASED;
|
||||
if (pgm_read_byte(p ++) == '-') {
|
||||
const char *q = p;
|
||||
while (! is_whitespace_or_nl_or_eol(char(pgm_read_byte(q))))
|
||||
++ q;
|
||||
n = q - p;
|
||||
if (n == strlen_P(STR_REVISION_DEV) && strncmp_PP(p, STR_REVISION_DEV, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_DEV;
|
||||
else if (n == strlen_P(STR_REVISION_ALPHA) && strncmp_PP(p, STR_REVISION_ALPHA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_ALPHA;
|
||||
else if (n == strlen_P(STR_REVISION_BETA) && strncmp_PP(p, STR_REVISION_BETA, n) == 0)
|
||||
version[3] = FIRMWARE_REVISION_BETA;
|
||||
else if ((n == 2 || n == 3) && strncmp_PP(p, STR_REVISION_RC, 2) == 0) {
|
||||
if (n == 2)
|
||||
version[3] = FIRMWARE_REVISION_RC;
|
||||
else {
|
||||
p += 2;
|
||||
if (is_digit(pgm_read_byte(p)))
|
||||
version[3] = FIRMWARE_REVISION_RC + pgm_read_byte(p) - '1';
|
||||
else
|
||||
return false;
|
||||
}
|
||||
} else
|
||||
return false;
|
||||
}
|
||||
|
||||
#if 0
|
||||
SERIAL_ECHOPGM("Version parsed, major: ");
|
||||
SERIAL_ECHO(version[0]);
|
||||
SERIAL_ECHOPGM(", minor: ");
|
||||
SERIAL_ECHO(version[1]);
|
||||
SERIAL_ECHOPGM(", revision: ");
|
||||
SERIAL_ECHO(version[2]);
|
||||
SERIAL_ECHOPGM(", flavor: ");
|
||||
SERIAL_ECHO(version[3]);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
// 1 - yes, 0 - false, -1 - error;
|
||||
inline int8_t is_provided_version_newer(const char *version_string)
|
||||
{
|
||||
uint16_t ver_gcode[3], ver_current[3];
|
||||
if (! parse_version(version_string, ver_gcode))
|
||||
return -1;
|
||||
if (! parse_version_P(FW_VERSION_STR, ver_current))
|
||||
return 0; // this shall not happen
|
||||
for (uint8_t i = 0; i < 3; ++ i)
|
||||
if (ver_gcode[i] > ver_current[i])
|
||||
return 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool show_upgrade_dialog_if_version_newer(const char *version_string)
|
||||
{
|
||||
uint16_t ver_gcode[4], ver_current[4];
|
||||
if (! parse_version(version_string, ver_gcode)) {
|
||||
// SERIAL_PROTOCOLLNPGM("parse_version failed");
|
||||
return false;
|
||||
}
|
||||
if (! parse_version_P(FW_VERSION_STR, ver_current)) {
|
||||
// SERIAL_PROTOCOLLNPGM("parse_version_P failed");
|
||||
return false; // this shall not happen
|
||||
}
|
||||
// SERIAL_PROTOCOLLNPGM("versions parsed");
|
||||
bool upgrade = false;
|
||||
for (uint8_t i = 0; i < 4; ++ i) {
|
||||
if (ver_gcode[i] > ver_current[i]) {
|
||||
upgrade = true;
|
||||
break;
|
||||
} else if (ver_gcode[i] < ver_current[i])
|
||||
break;
|
||||
}
|
||||
|
||||
if (upgrade) {
|
||||
lcd_display_message_fullscreen_P(MSG_NEW_FIRMWARE_AVAILABLE);
|
||||
lcd_print_at_PGM(0, 2, PSTR(""));
|
||||
for (const char *c = version_string; ! is_whitespace_or_nl_or_eol(*c); ++ c)
|
||||
lcd_implementation_write(*c);
|
||||
lcd_print_at_PGM(0, 3, MSG_NEW_FIRMWARE_PLEASE_UPGRADE);
|
||||
tone(BEEPER, 1000);
|
||||
delay_keep_alive(50);
|
||||
noTone(BEEPER);
|
||||
delay_keep_alive(500);
|
||||
tone(BEEPER, 1000);
|
||||
delay_keep_alive(50);
|
||||
noTone(BEEPER);
|
||||
lcd_wait_for_click();
|
||||
lcd_update_enable(true);
|
||||
lcd_implementation_clear();
|
||||
lcd_update();
|
||||
}
|
||||
|
||||
// Succeeded.
|
||||
return true;
|
||||
}
|
||||
|
||||
void update_current_firmware_version_to_eeprom()
|
||||
{
|
||||
for (int8_t i = 0; i < FW_PRUSA3D_MAGIC_LEN; ++ i)
|
||||
eeprom_update_byte((uint8_t*)(EEPROM_FIRMWARE_PRUSA_MAGIC+i), pgm_read_byte(FW_PRUSA3D_MAGIC_STR+i));
|
||||
uint16_t ver_current[4];
|
||||
if (parse_version_P(FW_VERSION_STR, ver_current)) {
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_MAJOR, ver_current[0]);
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_MINOR, ver_current[1]);
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_REVISION, ver_current[2]);
|
||||
// See FirmwareRevisionFlavorType for the definition of firmware flavors.
|
||||
eeprom_update_word((uint16_t*)EEPROM_FIRMWARE_VERSION_FLAVOR, ver_current[3]);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,24 +1,35 @@
|
|||
#ifndef UTIL_H
|
||||
#define UTIL_H
|
||||
|
||||
extern const char* FW_VERSION_STR_P();
|
||||
|
||||
// Definition of a firmware flavor numerical values.
|
||||
enum FirmwareRevisionFlavorType
|
||||
{
|
||||
FIRMWARE_REVISION_DEV = 0,
|
||||
FIRMWARE_REVISION_ALPHA = 1,
|
||||
FIRMWARE_REVISION_BETA = 2,
|
||||
FIRMWARE_REVISION_RC,
|
||||
FIRMWARE_REVISION_RC2,
|
||||
FIRMWARE_REVISION_RC3,
|
||||
FIRMWARE_REVISION_RC4,
|
||||
FIRMWARE_REVISION_RC5,
|
||||
FIRMWARE_REVISION_RELEASED = 127
|
||||
};
|
||||
|
||||
extern bool show_upgrade_dialog_if_version_newer(const char *version_string);
|
||||
|
||||
extern void update_current_firmware_version_to_eeprom();
|
||||
|
||||
#endif /* UTIL_H */
|
||||
#ifndef UTIL_H
|
||||
#define UTIL_H
|
||||
|
||||
extern const char* FW_VERSION_STR_P();
|
||||
|
||||
// Definition of a firmware flavor numerical values.
|
||||
enum FirmwareRevisionFlavorType
|
||||
{
|
||||
FIRMWARE_REVISION_DEV = 0,
|
||||
FIRMWARE_REVISION_ALPHA = 1,
|
||||
FIRMWARE_REVISION_BETA = 2,
|
||||
FIRMWARE_REVISION_RC,
|
||||
FIRMWARE_REVISION_RC2,
|
||||
FIRMWARE_REVISION_RC3,
|
||||
FIRMWARE_REVISION_RC4,
|
||||
FIRMWARE_REVISION_RC5,
|
||||
FIRMWARE_REVISION_RELEASED = 127
|
||||
};
|
||||
|
||||
extern bool show_upgrade_dialog_if_version_newer(const char *version_string);
|
||||
|
||||
extern void update_current_firmware_version_to_eeprom();
|
||||
|
||||
|
||||
|
||||
inline int8_t eeprom_read_int8(unsigned char* addr) {
|
||||
uint8_t v = eeprom_read_byte(addr);
|
||||
return *reinterpret_cast<int8_t*>(&v);
|
||||
}
|
||||
|
||||
inline void eeprom_update_int8(unsigned char* addr, int8_t v) {
|
||||
eeprom_update_byte(addr, *reinterpret_cast<uint8_t*>(&v));
|
||||
}
|
||||
|
||||
#endif /* UTIL_H */
|
||||
|
|
485
Firmware/variants/1_75mm_MK3-EINY03-E3Dv6full.h
Normal file
485
Firmware/variants/1_75mm_MK3-EINY03-E3Dv6full.h
Normal file
|
@ -0,0 +1,485 @@
|
|||
#ifndef CONFIGURATION_PRUSA_H
|
||||
#define CONFIGURATION_PRUSA_H
|
||||
|
||||
/*------------------------------------
|
||||
GENERAL SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Printer revision
|
||||
#define FILAMENT_SIZE "1_75mm_MK3"
|
||||
#define NOZZLE_TYPE "E3Dv6full"
|
||||
|
||||
// Developer flag
|
||||
#define DEVELOPER
|
||||
|
||||
// Printer name
|
||||
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
||||
|
||||
// Electronics
|
||||
#define MOTHERBOARD BOARD_EINY_0_3a
|
||||
|
||||
|
||||
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
||||
//#define E3D_PT100_EXTRUDER_WITH_AMP
|
||||
//#define E3D_PT100_EXTRUDER_NO_AMP
|
||||
//#define E3D_PT100_BED_WITH_AMP
|
||||
//#define E3D_PT100_BED_NO_AMP
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
AXIS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Steps per unit {X,Y,Z,E}
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280} //Extruder motor changed back to 200step type
|
||||
|
||||
// Endstop inverting
|
||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
|
||||
// Home position
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS -2.2
|
||||
#define MANUAL_Z_HOME_POS 0.2
|
||||
|
||||
// Travel limits after homing
|
||||
#define X_MAX_POS 255
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MAX_POS 210
|
||||
#define Y_MIN_POS -12 //orig -4
|
||||
#define Z_MAX_POS 210
|
||||
#define Z_MIN_POS 0.15
|
||||
|
||||
// Canceled home position
|
||||
#define X_CANCEL_POS 50
|
||||
#define Y_CANCEL_POS 190
|
||||
|
||||
//Pause print position
|
||||
#define X_PAUSE_POS 50
|
||||
#define Y_PAUSE_POS 190
|
||||
#define Z_PAUSE_LIFT 20
|
||||
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
|
||||
|
||||
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
|
||||
|
||||
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||
|
||||
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||
|
||||
#define Z_AXIS_ALWAYS_ON 1
|
||||
|
||||
//DEBUG
|
||||
#if 0
|
||||
#define DEBUG_DCODES //D codes
|
||||
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_BLINK_ACTIVE
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
TMC2130 default settings
|
||||
*------------------------------------*/
|
||||
|
||||
#define TMC2130_FCLK 12000000 // fclk = 12MHz
|
||||
|
||||
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis (increased from 16 to 32)
|
||||
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||
|
||||
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||
|
||||
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Y 210 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||
|
||||
/* //not used
|
||||
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
|
||||
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||
*/
|
||||
|
||||
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||
|
||||
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||
#define TMC2130_THIGH 0 // THIGH - unused
|
||||
|
||||
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
|
||||
|
||||
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||
#define TMC2130_SG_THRS_X 0 // stallguard sensitivity for X axis
|
||||
#define TMC2130_SG_THRS_Y 0 // stallguard sensitivity for Y axis
|
||||
#define TMC2130_SG_THRS_Z 2 // stallguard sensitivity for Z axis
|
||||
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||
|
||||
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
|
||||
#define TMC2130_CURRENTS_R {13, 18, 20, 22} // default running currents for all axes
|
||||
|
||||
//#define TMC2130_DEBUG
|
||||
//#define TMC2130_DEBUG_WR
|
||||
//#define TMC2130_DEBUG_RD
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
EXTRUDER SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Mintemps
|
||||
#define HEATER_0_MINTEMP 15
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define BED_MINTEMP 15
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define HEATER_0_MAXTEMP 410
|
||||
#else
|
||||
#define HEATER_0_MAXTEMP 305
|
||||
#endif
|
||||
#define HEATER_1_MAXTEMP 305
|
||||
#define HEATER_2_MAXTEMP 305
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_Kp 21.70
|
||||
#define DEFAULT_Ki 1.60
|
||||
#define DEFAULT_Kd 73.76
|
||||
#else
|
||||
// Define PID constants for extruder
|
||||
//#define DEFAULT_Kp 40.925
|
||||
//#define DEFAULT_Ki 4.875
|
||||
//#define DEFAULT_Kd 86.085
|
||||
#define DEFAULT_Kp 16.13
|
||||
#define DEFAULT_Ki 1.1625
|
||||
#define DEFAULT_Kd 56.23
|
||||
#endif
|
||||
|
||||
// Extrude mintemp
|
||||
#define EXTRUDE_MINTEMP 130
|
||||
|
||||
// Extruder cooling fans
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN 8
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
LOAD/UNLOAD FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Load filament commands
|
||||
#define LOAD_FILAMENT_0 "M83"
|
||||
#define LOAD_FILAMENT_1 "G1 E70 F400"
|
||||
#define LOAD_FILAMENT_2 "G1 E40 F100"
|
||||
|
||||
// Unload filament commands
|
||||
#define UNLOAD_FILAMENT_0 "M83"
|
||||
#define UNLOAD_FILAMENT_1 "G1 E-80 F7000"
|
||||
|
||||
/*------------------------------------
|
||||
CHANGE FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Filament change configuration
|
||||
#define FILAMENTCHANGEENABLE
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#define FILAMENTCHANGE_XPOS 211
|
||||
#define FILAMENTCHANGE_YPOS 0
|
||||
#define FILAMENTCHANGE_ZADD 2
|
||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||
#define FILAMENTCHANGE_FINALRETRACT -80
|
||||
|
||||
#define FILAMENTCHANGE_FIRSTFEED 70
|
||||
#define FILAMENTCHANGE_FINALFEED 50
|
||||
#define FILAMENTCHANGE_RECFEED 5
|
||||
|
||||
#define FILAMENTCHANGE_XYFEED 50
|
||||
#define FILAMENTCHANGE_EFEED 20
|
||||
#define FILAMENTCHANGE_RFEED 400
|
||||
#define FILAMENTCHANGE_EXFEED 2
|
||||
#define FILAMENTCHANGE_ZFEED 15
|
||||
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
ADDITIONAL FEATURES SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Prusa filament runout sensor
|
||||
//#define FILAMENT_RUNOUT_SUPPORT
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SUPPORT
|
||||
#define FILAMENT_RUNOUT_SENSOR 1
|
||||
#endif
|
||||
|
||||
// temperature runaway
|
||||
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||
|
||||
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||
|
||||
/*------------------------------------
|
||||
MOTOR CURRENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Motor Current setting for BIG RAMBo
|
||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||
|
||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
BED SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Mesh Bed Leveling system to enable it
|
||||
#define MESH_BED_LEVELING
|
||||
#ifdef MESH_BED_LEVELING
|
||||
|
||||
#define MBL_Z_STEP 0.01
|
||||
|
||||
// Mesh definitions
|
||||
#define MESH_MIN_X 35
|
||||
#define MESH_MAX_X 238
|
||||
#define MESH_MIN_Y 6
|
||||
#define MESH_MAX_Y 202
|
||||
|
||||
// Mesh upsample definition
|
||||
#define MESH_NUM_X_POINTS 7
|
||||
#define MESH_NUM_Y_POINTS 7
|
||||
// Mesh measure definition
|
||||
#define MESH_MEAS_NUM_X_POINTS 3
|
||||
#define MESH_MEAS_NUM_Y_POINTS 3
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
||||
#endif
|
||||
|
||||
// Bed Temperature Control
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
// Bed temperature compensation settings
|
||||
#define BED_OFFSET 10
|
||||
#define BED_OFFSET_START 40
|
||||
#define BED_OFFSET_CENTER 50
|
||||
|
||||
|
||||
#ifdef PIDTEMPBED
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_bedKp 21.70
|
||||
#define DEFAULT_bedKi 1.60
|
||||
#define DEFAULT_bedKd 73.76
|
||||
#else
|
||||
#define DEFAULT_bedKp 126.13
|
||||
#define DEFAULT_bedKi 4.30
|
||||
#define DEFAULT_bedKd 924.76
|
||||
#endif
|
||||
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from pidautotune
|
||||
// #define DEFAULT_bedKp 97.1
|
||||
// #define DEFAULT_bedKi 1.41
|
||||
// #define DEFAULT_bedKd 1675.16
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#endif // PIDTEMPBED
|
||||
|
||||
|
||||
/*-----------------------------------
|
||||
PREHEAT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 240
|
||||
#define PET_PREHEAT_HPB_TEMP 90
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
|
||||
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 1010 is Pt1000 with 1k pullup (non standard)
|
||||
// 147 is Pt100 with 4k7 pullup
|
||||
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
|
||||
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
|
||||
// 110 is Pt100 with 1k pullup (non standard)
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
|
||||
#define TEMP_SENSOR_0 247
|
||||
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define TEMP_SENSOR_0 148
|
||||
#else
|
||||
#define TEMP_SENSOR_0 5
|
||||
#endif
|
||||
#define TEMP_SENSOR_1 0
|
||||
#define TEMP_SENSOR_2 0
|
||||
#if defined(E3D_PT100_BED_WITH_AMP)
|
||||
#define TEMP_SENSOR_BED 247
|
||||
#elif defined(E3D_PT100_BED_NO_AMP)
|
||||
#define TEMP_SENSOR_BED 148
|
||||
#else
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#endif
|
||||
#define TEMP_SENSOR_PINDA 1
|
||||
#define TEMP_SENSOR_AMBIENT 2000
|
||||
|
||||
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||
|
||||
#define MAX_BED_TEMP_CALIBRATION 50
|
||||
#define MAX_HOTEND_TEMP_CALIBRATION 50
|
||||
|
||||
#define MAX_E_STEPS_PER_UNIT 250
|
||||
#define MIN_E_STEPS_PER_UNIT 100
|
||||
|
||||
#define Z_BABYSTEP_MIN -3999
|
||||
#define Z_BABYSTEP_MAX 0
|
||||
|
||||
#define PINDA_PREHEAT_X 70
|
||||
#define PINDA_PREHEAT_Y -3
|
||||
#define PINDA_PREHEAT_Z 1
|
||||
#define PINDA_HEAT_T 120 //time in s
|
||||
|
||||
#define PINDA_MIN_T 50
|
||||
#define PINDA_STEP_T 10
|
||||
#define PINDA_MAX_T 100
|
||||
|
||||
#define PING_TIME 60 //time in s
|
||||
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
|
||||
#define PING_ALLERT_PERIOD 60 //time in s
|
||||
|
||||
#define LONG_PRESS_TIME 1000 //time in ms for button long press
|
||||
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
|
||||
|
||||
#define DEFAULT_PID_TEMP 210
|
||||
|
||||
#define MIN_PRINT_FAN_SPEED 50
|
||||
|
||||
#ifdef SNMM
|
||||
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
|
||||
#else
|
||||
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||
#endif
|
||||
|
||||
#define UVLO_Z_AXIS_SHIFT 2
|
||||
|
||||
#endif //__CONFIGURATION_PRUSA_H
|
493
Firmware/variants/1_75mm_MK3-EINY04-E3Dv6full.h
Normal file
493
Firmware/variants/1_75mm_MK3-EINY04-E3Dv6full.h
Normal file
|
@ -0,0 +1,493 @@
|
|||
#ifndef CONFIGURATION_PRUSA_H
|
||||
#define CONFIGURATION_PRUSA_H
|
||||
|
||||
/*------------------------------------
|
||||
GENERAL SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Printer revision
|
||||
#define FILAMENT_SIZE "1_75mm_MK3"
|
||||
#define NOZZLE_TYPE "E3Dv6full"
|
||||
|
||||
// Developer flag
|
||||
#define DEVELOPER
|
||||
|
||||
// Printer name
|
||||
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
||||
|
||||
// Electronics
|
||||
#define MOTHERBOARD BOARD_EINY_0_4a
|
||||
|
||||
|
||||
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
||||
//#define E3D_PT100_EXTRUDER_WITH_AMP
|
||||
//#define E3D_PT100_EXTRUDER_NO_AMP
|
||||
//#define E3D_PT100_BED_WITH_AMP
|
||||
//#define E3D_PT100_BED_NO_AMP
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
AXIS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Steps per unit {X,Y,Z,E}
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
|
||||
|
||||
// Endstop inverting
|
||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
|
||||
// Home position
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS -2.2
|
||||
#define MANUAL_Z_HOME_POS 0.2
|
||||
|
||||
// Travel limits after homing
|
||||
#define X_MAX_POS 255
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MAX_POS 210
|
||||
#define Y_MIN_POS -12 //orig -4
|
||||
#define Z_MAX_POS 210
|
||||
#define Z_MIN_POS 0.15
|
||||
|
||||
// Canceled home position
|
||||
#define X_CANCEL_POS 50
|
||||
#define Y_CANCEL_POS 190
|
||||
|
||||
//Pause print position
|
||||
#define X_PAUSE_POS 50
|
||||
#define Y_PAUSE_POS 190
|
||||
#define Z_PAUSE_LIFT 20
|
||||
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {2500, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
|
||||
|
||||
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
|
||||
|
||||
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||
|
||||
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||
|
||||
#define Z_AXIS_ALWAYS_ON 1
|
||||
|
||||
//DEBUG
|
||||
#define DEBUG_DCODES //D codes
|
||||
#if 0
|
||||
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_BLINK_ACTIVE
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
TMC2130 default settings
|
||||
*------------------------------------*/
|
||||
|
||||
#define TMC2130_FCLK 12000000 // fclk = 12MHz
|
||||
|
||||
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis
|
||||
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||
|
||||
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||
|
||||
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Y 215 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||
|
||||
/* //not used
|
||||
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
|
||||
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||
*/
|
||||
|
||||
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||
|
||||
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||
#define TMC2130_THIGH 0 // THIGH - unused
|
||||
|
||||
#define TMC2130_TCOOLTHRS 500 // TCOOLTHRS - coolstep treshold
|
||||
|
||||
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||
#define TMC2130_SG_THRS_X 6 // stallguard sensitivity for X axis
|
||||
#define TMC2130_SG_THRS_Y 6 // stallguard sensitivity for Y axis
|
||||
#define TMC2130_SG_THRS_Z 3 // stallguard sensitivity for Z axis
|
||||
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||
|
||||
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
|
||||
#define TMC2130_CURRENTS_R {13, 31, 20, 22} // default running currents for all axes
|
||||
|
||||
//#define TMC2130_DEBUG
|
||||
//#define TMC2130_DEBUG_WR
|
||||
//#define TMC2130_DEBUG_RD
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
EXTRUDER SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Mintemps
|
||||
#define HEATER_0_MINTEMP 15
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define BED_MINTEMP 15
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define HEATER_0_MAXTEMP 410
|
||||
#else
|
||||
#define HEATER_0_MAXTEMP 305
|
||||
#endif
|
||||
#define HEATER_1_MAXTEMP 305
|
||||
#define HEATER_2_MAXTEMP 305
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_Kp 21.70
|
||||
#define DEFAULT_Ki 1.60
|
||||
#define DEFAULT_Kd 73.76
|
||||
#else
|
||||
// Define PID constants for extruder
|
||||
//#define DEFAULT_Kp 40.925
|
||||
//#define DEFAULT_Ki 4.875
|
||||
//#define DEFAULT_Kd 86.085
|
||||
#define DEFAULT_Kp 16.13
|
||||
#define DEFAULT_Ki 1.1625
|
||||
#define DEFAULT_Kd 56.23
|
||||
#endif
|
||||
|
||||
// Extrude mintemp
|
||||
#define EXTRUDE_MINTEMP 130
|
||||
|
||||
// Extruder cooling fans
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN 8
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
LOAD/UNLOAD FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Load filament commands
|
||||
#define LOAD_FILAMENT_0 "M83"
|
||||
#define LOAD_FILAMENT_1 "G1 E70 F400"
|
||||
#define LOAD_FILAMENT_2 "G1 E40 F100"
|
||||
|
||||
// Unload filament commands
|
||||
#define UNLOAD_FILAMENT_0 "M83"
|
||||
#define UNLOAD_FILAMENT_1 "G1 E-80 F7000"
|
||||
|
||||
/*------------------------------------
|
||||
CHANGE FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Filament change configuration
|
||||
#define FILAMENTCHANGEENABLE
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#define FILAMENTCHANGE_XPOS 211
|
||||
#define FILAMENTCHANGE_YPOS 0
|
||||
#define FILAMENTCHANGE_ZADD 2
|
||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||
#define FILAMENTCHANGE_FINALRETRACT -80
|
||||
|
||||
#define FILAMENTCHANGE_FIRSTFEED 70
|
||||
#define FILAMENTCHANGE_FINALFEED 50
|
||||
#define FILAMENTCHANGE_RECFEED 5
|
||||
|
||||
#define FILAMENTCHANGE_XYFEED 50
|
||||
#define FILAMENTCHANGE_EFEED 20
|
||||
#define FILAMENTCHANGE_RFEED 400
|
||||
#define FILAMENTCHANGE_EXFEED 2
|
||||
#define FILAMENTCHANGE_ZFEED 15
|
||||
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
ADDITIONAL FEATURES SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Prusa filament runout sensor
|
||||
//#define FILAMENT_RUNOUT_SUPPORT
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SUPPORT
|
||||
#define FILAMENT_RUNOUT_SENSOR 1
|
||||
#endif
|
||||
|
||||
// temperature runaway
|
||||
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||
|
||||
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||
|
||||
/*------------------------------------
|
||||
MOTOR CURRENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Motor Current setting for BIG RAMBo
|
||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||
|
||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
BED SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Mesh Bed Leveling system to enable it
|
||||
#define MESH_BED_LEVELING
|
||||
#ifdef MESH_BED_LEVELING
|
||||
|
||||
#define MBL_Z_STEP 0.01
|
||||
|
||||
// Mesh definitions
|
||||
#define MESH_MIN_X 35
|
||||
#define MESH_MAX_X 238
|
||||
#define MESH_MIN_Y 6
|
||||
#define MESH_MAX_Y 202
|
||||
|
||||
// Mesh upsample definition
|
||||
#define MESH_NUM_X_POINTS 7
|
||||
#define MESH_NUM_Y_POINTS 7
|
||||
// Mesh measure definition
|
||||
#define MESH_MEAS_NUM_X_POINTS 3
|
||||
#define MESH_MEAS_NUM_Y_POINTS 3
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
||||
#endif
|
||||
|
||||
// Bed Temperature Control
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
// Bed temperature compensation settings
|
||||
#define BED_OFFSET 10
|
||||
#define BED_OFFSET_START 40
|
||||
#define BED_OFFSET_CENTER 50
|
||||
|
||||
|
||||
#ifdef PIDTEMPBED
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_bedKp 21.70
|
||||
#define DEFAULT_bedKi 1.60
|
||||
#define DEFAULT_bedKd 73.76
|
||||
#else
|
||||
#define DEFAULT_bedKp 126.13
|
||||
#define DEFAULT_bedKi 4.30
|
||||
#define DEFAULT_bedKd 924.76
|
||||
#endif
|
||||
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from pidautotune
|
||||
// #define DEFAULT_bedKp 97.1
|
||||
// #define DEFAULT_bedKi 1.41
|
||||
// #define DEFAULT_bedKd 1675.16
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#endif // PIDTEMPBED
|
||||
|
||||
|
||||
/*-----------------------------------
|
||||
PREHEAT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 240
|
||||
#define PET_PREHEAT_HPB_TEMP 90
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
|
||||
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 1010 is Pt1000 with 1k pullup (non standard)
|
||||
// 147 is Pt100 with 4k7 pullup
|
||||
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
|
||||
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
|
||||
// 110 is Pt100 with 1k pullup (non standard)
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
|
||||
#define TEMP_SENSOR_0 247
|
||||
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define TEMP_SENSOR_0 148
|
||||
#else
|
||||
#define TEMP_SENSOR_0 5
|
||||
#endif
|
||||
#define TEMP_SENSOR_1 0
|
||||
#define TEMP_SENSOR_2 0
|
||||
#if defined(E3D_PT100_BED_WITH_AMP)
|
||||
#define TEMP_SENSOR_BED 247
|
||||
#elif defined(E3D_PT100_BED_NO_AMP)
|
||||
#define TEMP_SENSOR_BED 148
|
||||
#else
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#endif
|
||||
#define TEMP_SENSOR_PINDA 1
|
||||
#define TEMP_SENSOR_AMBIENT 2000
|
||||
|
||||
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||
|
||||
#define MAX_BED_TEMP_CALIBRATION 50
|
||||
#define MAX_HOTEND_TEMP_CALIBRATION 50
|
||||
|
||||
#define MAX_E_STEPS_PER_UNIT 250
|
||||
#define MIN_E_STEPS_PER_UNIT 100
|
||||
|
||||
#define Z_BABYSTEP_MIN -3999
|
||||
#define Z_BABYSTEP_MAX 0
|
||||
|
||||
#define PINDA_PREHEAT_X 70
|
||||
#define PINDA_PREHEAT_Y -3
|
||||
#define PINDA_PREHEAT_Z 1
|
||||
#define PINDA_HEAT_T 120 //time in s
|
||||
|
||||
#define PINDA_MIN_T 50
|
||||
#define PINDA_STEP_T 10
|
||||
#define PINDA_MAX_T 100
|
||||
|
||||
#define PING_TIME 60 //time in s
|
||||
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
|
||||
#define PING_ALLERT_PERIOD 60 //time in s
|
||||
|
||||
#define LONG_PRESS_TIME 1000 //time in ms for button long press
|
||||
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
|
||||
|
||||
#define DEFAULT_PID_TEMP 210
|
||||
|
||||
#define MIN_PRINT_FAN_SPEED 75
|
||||
|
||||
#ifdef SNMM
|
||||
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
|
||||
#else
|
||||
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||
#endif
|
||||
|
||||
// How much shall the print head be lifted on power panic?
|
||||
// Ideally the Z axis will reach a zero phase of the stepper driver on power outage. To simplify this,
|
||||
// UVLO_Z_AXIS_SHIFT shall be an integer multiply of the stepper driver cycle, that is 4x full step.
|
||||
// For example, the Prusa i3 MK2 with 16 microsteps per full step has Z stepping of 400 microsteps per mm.
|
||||
// At 400 microsteps per mm, a full step lifts the Z axis by 0.04mm, and a stepper driver cycle is 0.16mm.
|
||||
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
|
||||
#define UVLO_Z_AXIS_SHIFT 1.92
|
||||
|
||||
#define HEATBED_V2
|
||||
|
||||
#endif //__CONFIGURATION_PRUSA_H
|
512
Firmware/variants/1_75mm_MK3-EINY10a-E3Dv6full.h
Normal file
512
Firmware/variants/1_75mm_MK3-EINY10a-E3Dv6full.h
Normal file
|
@ -0,0 +1,512 @@
|
|||
#ifndef CONFIGURATION_PRUSA_H
|
||||
#define CONFIGURATION_PRUSA_H
|
||||
|
||||
/*------------------------------------
|
||||
GENERAL SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Printer revision
|
||||
#define FILAMENT_SIZE "1_75mm_MK3"
|
||||
#define NOZZLE_TYPE "E3Dv6full"
|
||||
|
||||
// Developer flag
|
||||
#define DEVELOPER
|
||||
|
||||
// Printer name
|
||||
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
|
||||
|
||||
// Electronics
|
||||
#define MOTHERBOARD BOARD_EINY_0_4a
|
||||
|
||||
|
||||
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
|
||||
//#define E3D_PT100_EXTRUDER_WITH_AMP
|
||||
//#define E3D_PT100_EXTRUDER_NO_AMP
|
||||
//#define E3D_PT100_BED_WITH_AMP
|
||||
//#define E3D_PT100_BED_NO_AMP
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
AXIS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Steps per unit {X,Y,Z,E}
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,560}
|
||||
|
||||
// Endstop inverting
|
||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||
|
||||
// Home position
|
||||
#define MANUAL_X_HOME_POS 0
|
||||
#define MANUAL_Y_HOME_POS -2.2
|
||||
#define MANUAL_Z_HOME_POS 0.2
|
||||
|
||||
// Travel limits after homing
|
||||
#define X_MAX_POS 255
|
||||
#define X_MIN_POS 0
|
||||
#define Y_MAX_POS 210
|
||||
#define Y_MIN_POS -12 //orig -4
|
||||
#define Z_MAX_POS 210
|
||||
#define Z_MIN_POS 0.15
|
||||
|
||||
// Canceled home position
|
||||
#define X_CANCEL_POS 50
|
||||
#define Y_CANCEL_POS 190
|
||||
|
||||
//Pause print position
|
||||
#define X_PAUSE_POS 50
|
||||
#define Y_PAUSE_POS 190
|
||||
#define Z_PAUSE_LIFT 20
|
||||
|
||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||
#define HOMING_FEEDRATE {2500, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
|
||||
|
||||
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
|
||||
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
|
||||
|
||||
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||
|
||||
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
|
||||
//#define MAX_SILENT_FEEDRATE 2700 //
|
||||
|
||||
#define Z_AXIS_ALWAYS_ON 1
|
||||
|
||||
// Automatic recovery after crash is detected
|
||||
#define AUTOMATIC_RECOVERY_AFTER_CRASH
|
||||
|
||||
//DEBUG
|
||||
#define DEBUG_DCODES //D codes
|
||||
#if 1
|
||||
//#define DEBUG_FSENSOR_LOG //Reports fsensor status to serial
|
||||
//#define DEBUG_CRASHDET_COUNTERS //Display crash-detection counters on LCD
|
||||
//#define DEBUG_RESUME_PRINT //Resume/save print debug enable
|
||||
//#define DEBUG_UVLO_AUTOMATIC_RECOVER // Power panic automatic recovery debug output
|
||||
//#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
|
||||
//#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
|
||||
//#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
|
||||
//#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
|
||||
//#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
|
||||
//#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
|
||||
#define DEBUG_DISABLE_STARTMSGS //no startup messages
|
||||
//#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
|
||||
//#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
|
||||
//#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
|
||||
//#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
|
||||
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
|
||||
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
|
||||
//#define DEBUG_BLINK_ACTIVE
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
TMC2130 default settings
|
||||
*------------------------------------*/
|
||||
|
||||
#define TMC2130_FCLK 12000000 // fclk = 12MHz
|
||||
|
||||
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
|
||||
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
|
||||
#define TMC2130_USTEPS_E 64 // microstep resolution for E axis
|
||||
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
|
||||
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
|
||||
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
|
||||
|
||||
#define TMC2130_PWM_GRAD_X 2 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_X 230 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
|
||||
|
||||
#define TMC2130_PWM_GRAD_Y 2 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Y 235 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
|
||||
|
||||
/* //not used
|
||||
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
|
||||
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
|
||||
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
|
||||
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
|
||||
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
|
||||
*/
|
||||
|
||||
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
|
||||
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
|
||||
|
||||
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
|
||||
#define TMC2130_THIGH 0 // THIGH - unused
|
||||
|
||||
//#define TMC2130_TCOOLTHRS_X 450 // TCOOLTHRS - coolstep treshold
|
||||
//#define TMC2130_TCOOLTHRS_Y 450 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_X 430 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_Y 430 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_Z 500 // TCOOLTHRS - coolstep treshold
|
||||
#define TMC2130_TCOOLTHRS_E 500 // TCOOLTHRS - coolstep treshold
|
||||
|
||||
#define TMC2130_SG_HOMING 1 // stallguard homing
|
||||
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
|
||||
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
|
||||
#define TMC2130_SG_THRS_X 1 // stallguard sensitivity for X axis
|
||||
#define TMC2130_SG_THRS_Y 3 // stallguard sensitivity for Y axis
|
||||
#define TMC2130_SG_THRS_Z 3 // stallguard sensitivity for Z axis
|
||||
#define TMC2130_SG_THRS_E 3 // stallguard sensitivity for E axis
|
||||
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
|
||||
|
||||
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||
#define TMC2130_CURRENTS_H {3, 3, 20, 28} // default holding currents for all axes
|
||||
#define TMC2130_CURRENTS_R {13, 20, 20, 28} // default running currents for all axes
|
||||
|
||||
//#define TMC2130_DEBUG
|
||||
//#define TMC2130_DEBUG_WR
|
||||
//#define TMC2130_DEBUG_RD
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
EXTRUDER SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Mintemps
|
||||
#define HEATER_0_MINTEMP 15
|
||||
#define HEATER_1_MINTEMP 5
|
||||
#define HEATER_2_MINTEMP 5
|
||||
#define BED_MINTEMP 15
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define HEATER_0_MAXTEMP 410
|
||||
#else
|
||||
#define HEATER_0_MAXTEMP 305
|
||||
#endif
|
||||
#define HEATER_1_MAXTEMP 305
|
||||
#define HEATER_2_MAXTEMP 305
|
||||
#define BED_MAXTEMP 150
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_Kp 21.70
|
||||
#define DEFAULT_Ki 1.60
|
||||
#define DEFAULT_Kd 73.76
|
||||
#else
|
||||
// Define PID constants for extruder
|
||||
//#define DEFAULT_Kp 40.925
|
||||
//#define DEFAULT_Ki 4.875
|
||||
//#define DEFAULT_Kd 86.085
|
||||
#define DEFAULT_Kp 16.13
|
||||
#define DEFAULT_Ki 1.1625
|
||||
#define DEFAULT_Kd 56.23
|
||||
#endif
|
||||
|
||||
// Extrude mintemp
|
||||
#define EXTRUDE_MINTEMP 130
|
||||
|
||||
// Extruder cooling fans
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN 8
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
|
||||
|
||||
/*------------------------------------
|
||||
LOAD/UNLOAD FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Load filament commands
|
||||
#define LOAD_FILAMENT_0 "M83"
|
||||
#define LOAD_FILAMENT_1 "G1 E70 F400"
|
||||
#define LOAD_FILAMENT_2 "G1 E40 F100"
|
||||
|
||||
// Unload filament commands
|
||||
#define UNLOAD_FILAMENT_0 "M83"
|
||||
#define UNLOAD_FILAMENT_1 "G1 E-80 F7000"
|
||||
|
||||
/*------------------------------------
|
||||
CHANGE FILAMENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Filament change configuration
|
||||
#define FILAMENTCHANGEENABLE
|
||||
#ifdef FILAMENTCHANGEENABLE
|
||||
#define FILAMENTCHANGE_XPOS 211
|
||||
#define FILAMENTCHANGE_YPOS 0
|
||||
#define FILAMENTCHANGE_ZADD 2
|
||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||
#define FILAMENTCHANGE_FINALRETRACT -80
|
||||
|
||||
#define FILAMENTCHANGE_FIRSTFEED 70
|
||||
#define FILAMENTCHANGE_FINALFEED 50
|
||||
#define FILAMENTCHANGE_RECFEED 5
|
||||
|
||||
#define FILAMENTCHANGE_XYFEED 50
|
||||
#define FILAMENTCHANGE_EFEED 20
|
||||
//#define FILAMENTCHANGE_RFEED 400
|
||||
#define FILAMENTCHANGE_RFEED 7000 / 60
|
||||
#define FILAMENTCHANGE_EXFEED 2
|
||||
#define FILAMENTCHANGE_ZFEED 15
|
||||
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
ADDITIONAL FEATURES SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Prusa filament runout sensor
|
||||
//#define FILAMENT_RUNOUT_SUPPORT
|
||||
|
||||
#ifdef FILAMENT_RUNOUT_SUPPORT
|
||||
#define FILAMENT_RUNOUT_SENSOR 1
|
||||
#endif
|
||||
|
||||
// temperature runaway
|
||||
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||
|
||||
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||
|
||||
/*------------------------------------
|
||||
MOTOR CURRENT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Motor Current setting for BIG RAMBo
|
||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
||||
|
||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
||||
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
|
||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
|
||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
|
||||
#endif
|
||||
|
||||
/*------------------------------------
|
||||
BED SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
// Define Mesh Bed Leveling system to enable it
|
||||
#define MESH_BED_LEVELING
|
||||
#ifdef MESH_BED_LEVELING
|
||||
|
||||
#define MBL_Z_STEP 0.01
|
||||
|
||||
// Mesh definitions
|
||||
#define MESH_MIN_X 35
|
||||
#define MESH_MAX_X 238
|
||||
#define MESH_MIN_Y 6
|
||||
#define MESH_MAX_Y 202
|
||||
|
||||
// Mesh upsample definition
|
||||
#define MESH_NUM_X_POINTS 7
|
||||
#define MESH_NUM_Y_POINTS 7
|
||||
// Mesh measure definition
|
||||
#define MESH_MEAS_NUM_X_POINTS 3
|
||||
#define MESH_MEAS_NUM_Y_POINTS 3
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
||||
#endif
|
||||
|
||||
// Bed Temperature Control
|
||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||
//
|
||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||
// If this is enabled, find your own PID constants below.
|
||||
#define PIDTEMPBED
|
||||
//
|
||||
//#define BED_LIMIT_SWITCHING
|
||||
|
||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||
|
||||
// Bed temperature compensation settings
|
||||
#define BED_OFFSET 10
|
||||
#define BED_OFFSET_START 40
|
||||
#define BED_OFFSET_CENTER 50
|
||||
|
||||
|
||||
#ifdef PIDTEMPBED
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
|
||||
// Define PID constants for extruder with PT100
|
||||
#define DEFAULT_bedKp 21.70
|
||||
#define DEFAULT_bedKi 1.60
|
||||
#define DEFAULT_bedKd 73.76
|
||||
#else
|
||||
#define DEFAULT_bedKp 126.13
|
||||
#define DEFAULT_bedKi 4.30
|
||||
#define DEFAULT_bedKd 924.76
|
||||
#endif
|
||||
|
||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
//from pidautotune
|
||||
// #define DEFAULT_bedKp 97.1
|
||||
// #define DEFAULT_bedKi 1.41
|
||||
// #define DEFAULT_bedKd 1675.16
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#endif // PIDTEMPBED
|
||||
|
||||
|
||||
/*-----------------------------------
|
||||
PREHEAT SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 240
|
||||
#define PET_PREHEAT_HPB_TEMP 90
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
*------------------------------------*/
|
||||
|
||||
//
|
||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||
//
|
||||
//// Temperature sensor settings:
|
||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||
// -1 is thermocouple with AD595
|
||||
// 0 is not used
|
||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
|
||||
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||
//
|
||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||
// (but gives greater accuracy and more stable PID)
|
||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
||||
//
|
||||
// 1047 is Pt1000 with 4k7 pullup
|
||||
// 1010 is Pt1000 with 1k pullup (non standard)
|
||||
// 147 is Pt100 with 4k7 pullup
|
||||
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
|
||||
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
|
||||
// 110 is Pt100 with 1k pullup (non standard)
|
||||
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
|
||||
#define TEMP_SENSOR_0 247
|
||||
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
#define TEMP_SENSOR_0 148
|
||||
#else
|
||||
#define TEMP_SENSOR_0 5
|
||||
#endif
|
||||
#define TEMP_SENSOR_1 0
|
||||
#define TEMP_SENSOR_2 0
|
||||
#if defined(E3D_PT100_BED_WITH_AMP)
|
||||
#define TEMP_SENSOR_BED 247
|
||||
#elif defined(E3D_PT100_BED_NO_AMP)
|
||||
#define TEMP_SENSOR_BED 148
|
||||
#else
|
||||
#define TEMP_SENSOR_BED 1
|
||||
#endif
|
||||
#define TEMP_SENSOR_PINDA 1
|
||||
#define TEMP_SENSOR_AMBIENT 2000
|
||||
|
||||
#define STACK_GUARD_TEST_VALUE 0xA2A2
|
||||
|
||||
#define MAX_BED_TEMP_CALIBRATION 50
|
||||
#define MAX_HOTEND_TEMP_CALIBRATION 50
|
||||
|
||||
#define MAX_E_STEPS_PER_UNIT 250
|
||||
#define MIN_E_STEPS_PER_UNIT 100
|
||||
|
||||
#define Z_BABYSTEP_MIN -3999
|
||||
#define Z_BABYSTEP_MAX 0
|
||||
|
||||
#define PINDA_PREHEAT_X 70
|
||||
#define PINDA_PREHEAT_Y -3
|
||||
#define PINDA_PREHEAT_Z 1
|
||||
#define PINDA_HEAT_T 120 //time in s
|
||||
|
||||
#define PINDA_MIN_T 50
|
||||
#define PINDA_STEP_T 10
|
||||
#define PINDA_MAX_T 100
|
||||
|
||||
#define PING_TIME 60 //time in s
|
||||
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
|
||||
#define PING_ALLERT_PERIOD 60 //time in s
|
||||
|
||||
#define LONG_PRESS_TIME 1000 //time in ms for button long press
|
||||
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
|
||||
|
||||
#define DEFAULT_PID_TEMP 210
|
||||
|
||||
#define MIN_PRINT_FAN_SPEED 75
|
||||
|
||||
#ifdef SNMM
|
||||
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
|
||||
#else
|
||||
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
|
||||
#endif
|
||||
|
||||
// How much shall the print head be lifted on power panic?
|
||||
// Ideally the Z axis will reach a zero phase of the stepper driver on power outage. To simplify this,
|
||||
// UVLO_Z_AXIS_SHIFT shall be an integer multiply of the stepper driver cycle, that is 4x full step.
|
||||
// For example, the Prusa i3 MK2 with 16 microsteps per full step has Z stepping of 400 microsteps per mm.
|
||||
// At 400 microsteps per mm, a full step lifts the Z axis by 0.04mm, and a stepper driver cycle is 0.16mm.
|
||||
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
|
||||
#define UVLO_Z_AXIS_SHIFT 1.92
|
||||
// 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
|
||||
|
||||
//#define SUPPORT_VERBOSITY
|
||||
|
||||
#endif //__CONFIGURATION_PRUSA_H
|
10
README.md
10
README.md
|
@ -1,10 +1,10 @@
|
|||
# Original Prusa i3 Plus Firmware
|
||||
# Original Prusa i3 MK2 Firmware
|
||||
|
||||
## General instructions
|
||||
|
||||
Pre-compiled hex files for all printers by PRUSA RESEARCH are available in hex_files folder.
|
||||
Pre-compiled hex output on PRUSA RESEARCH site: http://prusa3d.com/downloads/firmware/
|
||||
|
||||
Just clone the repo and flash it to the firmware
|
||||
Just download and flash it to the electronics
|
||||
|
||||
|
||||
## Build instructions
|
||||
|
@ -19,11 +19,11 @@ Remove Liquid Crystal library from your arduino or rename it
|
|||
|
||||
### Step 3
|
||||
|
||||
Install the arduino addon in root of this repo
|
||||
Install the arduino addon located in the root of this repo. Don't forget to install correct version!
|
||||
|
||||
### Step 4
|
||||
|
||||
Copy one of the configuration from variants folder to the the Firmware folder
|
||||
Copy the configuration file matching your printer from variants folder to the the Firmware folder
|
||||
|
||||
### Step 5
|
||||
|
||||
|
|
Loading…
Reference in a new issue