Updated repetier
This commit is contained in:
parent
a0bb6d8315
commit
cbaa0cb12d
33 changed files with 18923 additions and 17089 deletions
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -23,19 +23,19 @@
|
|||
|
||||
#if UI_DISPLAY_TYPE != NO_DISPLAY
|
||||
uint8_t Com::selectedLanguage;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef MACHINE_TYPE
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
#define MACHINE_TYPE "Delta"
|
||||
#elif DRIVE_SYSTEM == CARTESIAN
|
||||
#define MACHINE_TYPE "Mendel"
|
||||
#else
|
||||
#define MACHINE_TYPE "Core_XY"
|
||||
#endif
|
||||
#endif
|
||||
#ifndef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "https://github.com/repetier/Repetier-Firmware/"
|
||||
#endif
|
||||
#endif
|
||||
#ifndef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "https://github.com/repetier/Repetier-Firmware/"
|
||||
#endif // FIRMWARE_URL
|
||||
FSTRINGVALUE(Com::tFirmware,"FIRMWARE_NAME:Repetier_" REPETIER_VERSION " FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:1.0 MACHINE_TYPE:" MACHINE_TYPE " EXTRUDER_COUNT:" XSTR(NUM_EXTRUDER) " REPETIER_PROTOCOL:3")
|
||||
FSTRINGVALUE(Com::tDebug,"Debug:")
|
||||
|
@ -91,19 +91,20 @@ FSTRINGVALUE(Com::tSpaceRaw," RAW")
|
|||
FSTRINGVALUE(Com::tColon,":")
|
||||
FSTRINGVALUE(Com::tSlash,"/")
|
||||
FSTRINGVALUE(Com::tSpaceSlash," /")
|
||||
#if JSON_OUTPUT
|
||||
FSTRINGVALUE(Com::tJSONDir,"{\"dir\":\"")
|
||||
FSTRINGVALUE(Com::tJSONFiles,"\",\"files\":[")
|
||||
FSTRINGVALUE(Com::tJSONArrayEnd,"]}")
|
||||
FSTRINGVALUE(Com::tJSONErrorStart,"{\"err\":\"")
|
||||
FSTRINGVALUE(Com::tJSONErrorEnd,"\"}")
|
||||
FSTRINGVALUE(Com::tJSONFileInfoStart, "{\"err\":0,\"size\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoHeight, ",\"height\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoLayerHeight, ",\"layerHeight\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoFilament, ",\"filament\":[");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoGeneratedBy, "],\"generatedBy\":\"");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoName, ",\"fileName\":\"");
|
||||
#endif // JSON_OUTPUT
|
||||
FSTRINGVALUE(Com::tFatal,"fatal:")
|
||||
#if JSON_OUTPUT
|
||||
FSTRINGVALUE(Com::tJSONDir,"{\"dir\":\"")
|
||||
FSTRINGVALUE(Com::tJSONFiles,"\",\"files\":[")
|
||||
FSTRINGVALUE(Com::tJSONArrayEnd,"]}")
|
||||
FSTRINGVALUE(Com::tJSONErrorStart,"{\"err\":\"")
|
||||
FSTRINGVALUE(Com::tJSONErrorEnd,"\"}")
|
||||
FSTRINGVALUE(Com::tJSONFileInfoStart, "{\"err\":0,\"size\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoHeight, ",\"height\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoLayerHeight, ",\"layerHeight\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoFilament, ",\"filament\":[");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoGeneratedBy, "],\"generatedBy\":\"");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoName, ",\"fileName\":\"");
|
||||
#endif // JSON_OUTPUT
|
||||
FSTRINGVALUE(Com::tSpeedMultiply,"SpeedMultiply:")
|
||||
FSTRINGVALUE(Com::tFlowMultiply,"FlowMultiply:")
|
||||
FSTRINGVALUE(Com::tFanspeed,"Fanspeed:")
|
||||
|
@ -153,7 +154,6 @@ FSTRINGVALUE(Com::tMeasureDeltaSteps,"Measure/delta (Steps) =")
|
|||
FSTRINGVALUE(Com::tMeasureDelta,"Measure/delta =")
|
||||
FSTRINGVALUE(Com::tMeasureOriginReset,"Measured origin set. Measurement reset.")
|
||||
FSTRINGVALUE(Com::tMeasurementAbortedOrigin,"Origin measurement cannot be set. Use only Z-Cartesian (straight up and down) movements and try again.")
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate,"Invalid delta coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tLevelingCalc,"Leveling calc:")
|
||||
FSTRINGVALUE(Com::tTower1,"Tower 1:")
|
||||
FSTRINGVALUE(Com::tTower2,"Tower 2:")
|
||||
|
@ -164,11 +164,21 @@ FSTRINGVALUE(Com::tDeltaAlphaC,"Alpha C(90):")
|
|||
FSTRINGVALUE(Com::tDeltaRadiusCorrectionA,"Delta Radius A(0):")
|
||||
FSTRINGVALUE(Com::tDeltaRadiusCorrectionB,"Delta Radius B(0):")
|
||||
FSTRINGVALUE(Com::tDeltaRadiusCorrectionC,"Delta Radius C(0):")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment,"No move in delta segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#endif // DRIVE_SYSTEM
|
||||
#if DRIVE_SYSTEM==TUGA
|
||||
#if NONLINEAR_SYSTEM
|
||||
#if DRIVE_SYSTEM == TUGA
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate,"Invalid coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment,"No move in delta segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#elif DRIVE_SYSTEM == DELTA
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate,"Invalid delta coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment,"No move in delta segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#else
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate,"Invalid coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment,"No move in segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if DRIVE_SYSTEM==TUGA
|
||||
FSTRINGVALUE(Com::tEPRDiagonalRodLength,"Long arm length [mm]")
|
||||
#endif // DRIVE_SYSTEM
|
||||
#ifdef DEBUG_GENERIC
|
||||
|
@ -187,7 +197,7 @@ FSTRINGVALUE(Com::tAPIDClassic," Classic PID")
|
|||
FSTRINGVALUE(Com::tAPIDKp," Kp: ")
|
||||
FSTRINGVALUE(Com::tAPIDKi," Ki: ")
|
||||
FSTRINGVALUE(Com::tAPIDKd," Kd: ")
|
||||
FSTRINGVALUE(Com::tAPIDFailedHigh,"PID Autotune failed! Temperature to high")
|
||||
FSTRINGVALUE(Com::tAPIDFailedHigh,"PID Autotune failed! Temperature too high")
|
||||
FSTRINGVALUE(Com::tAPIDFailedTimeout,"PID Autotune failed! timeout")
|
||||
FSTRINGVALUE(Com::tAPIDFinished,"PID Autotune finished ! Place the Kp, Ki and Kd constants in the Configuration.h or EEPROM")
|
||||
FSTRINGVALUE(Com::tMTEMPColon,"MTEMP:")
|
||||
|
@ -308,6 +318,10 @@ FSTRINGVALUE(Com::tEPRYBacklash,"Y backlash [mm]")
|
|||
FSTRINGVALUE(Com::tEPRZBacklash,"Z backlash [mm]")
|
||||
FSTRINGVALUE(Com::tEPRMaxJerk,"Max. jerk [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRAccelerationFactorAtTop,"Acceleration factor at top [%,100=like bottom]")
|
||||
#if NONLINEAR_SYSTEM
|
||||
FSTRINGVALUE(Com::tEPRSegmentsPerSecondPrint,"Segments/s for printing")
|
||||
FSTRINGVALUE(Com::tEPRSegmentsPerSecondTravel,"Segments/s for travel")
|
||||
#endif
|
||||
#if DRIVE_SYSTEM==DELTA
|
||||
FSTRINGVALUE(Com::tEPRZAcceleration,"Acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRZTravelAcceleration,"Travel acceleration [mm/s^2]")
|
||||
|
@ -317,8 +331,6 @@ FSTRINGVALUE(Com::tEPRZHomingFeedrate,"Homing feedrate [mm/s]")
|
|||
|
||||
FSTRINGVALUE(Com::tEPRDiagonalRodLength,"Diagonal rod length [mm]")
|
||||
FSTRINGVALUE(Com::tEPRHorizontalRadius,"Horizontal rod radius at 0,0 [mm]")
|
||||
FSTRINGVALUE(Com::tEPRSegmentsPerSecondPrint,"Segments/s for printing")
|
||||
FSTRINGVALUE(Com::tEPRSegmentsPerSecondTravel,"Segments/s for travel")
|
||||
|
||||
FSTRINGVALUE(Com::tEPRTowerXOffset,"Tower X endstop offset [steps]")
|
||||
FSTRINGVALUE(Com::tEPRTowerYOffset,"Tower Y endstop offset [steps]")
|
||||
|
@ -428,9 +440,9 @@ FSTRINGVALUE(Com::tExtrDot,"Extr.")
|
|||
FSTRINGVALUE(Com::tMCPEpromSettings, "MCP4728 DAC EEPROM Settings:")
|
||||
FSTRINGVALUE(Com::tMCPCurrentSettings,"MCP4728 DAC Current Settings:")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tPrinterModeFFF,"PrinterMode:FFF")
|
||||
FSTRINGVALUE(Com::tPrinterModeLaser,"PrinterMode:Laser")
|
||||
FSTRINGVALUE(Com::tPrinterModeCNC,"PrinterMode:CNC")
|
||||
FSTRINGVALUE(Com::tPrinterModeFFF,"PrinterMode:FFF")
|
||||
FSTRINGVALUE(Com::tPrinterModeLaser,"PrinterMode:Laser")
|
||||
FSTRINGVALUE(Com::tPrinterModeCNC,"PrinterMode:CNC")
|
||||
#ifdef STARTUP_GCODE
|
||||
FSTRINGVALUE(Com::tStartupGCode,STARTUP_GCODE)
|
||||
#endif
|
||||
|
|
|
@ -66,19 +66,20 @@ FSTRINGVAR(tUnknownCommand)
|
|||
FSTRINGVAR(tFreeRAM)
|
||||
FSTRINGVAR(tXColon)
|
||||
FSTRINGVAR(tSlash)
|
||||
FSTRINGVAR(tSpaceSlash)
|
||||
#if JSON_OUTPUT
|
||||
FSTRINGVAR(tJSONDir)
|
||||
FSTRINGVAR(tJSONFiles)
|
||||
FSTRINGVAR(tJSONArrayEnd)
|
||||
FSTRINGVAR(tJSONErrorStart)
|
||||
FSTRINGVAR(tJSONErrorEnd)
|
||||
FSTRINGVAR(tJSONFileInfoStart)
|
||||
FSTRINGVAR(tJSONFileInfoHeight)
|
||||
FSTRINGVAR(tJSONFileInfoLayerHeight)
|
||||
FSTRINGVAR(tJSONFileInfoFilament)
|
||||
FSTRINGVAR(tJSONFileInfoGeneratedBy)
|
||||
FSTRINGVAR(tJSONFileInfoName)
|
||||
FSTRINGVAR(tSpaceSlash)
|
||||
FSTRINGVAR(tFatal)
|
||||
#if JSON_OUTPUT
|
||||
FSTRINGVAR(tJSONDir)
|
||||
FSTRINGVAR(tJSONFiles)
|
||||
FSTRINGVAR(tJSONArrayEnd)
|
||||
FSTRINGVAR(tJSONErrorStart)
|
||||
FSTRINGVAR(tJSONErrorEnd)
|
||||
FSTRINGVAR(tJSONFileInfoStart)
|
||||
FSTRINGVAR(tJSONFileInfoHeight)
|
||||
FSTRINGVAR(tJSONFileInfoLayerHeight)
|
||||
FSTRINGVAR(tJSONFileInfoFilament)
|
||||
FSTRINGVAR(tJSONFileInfoGeneratedBy)
|
||||
FSTRINGVAR(tJSONFileInfoName)
|
||||
#endif
|
||||
FSTRINGVAR(tSpaceXColon)
|
||||
FSTRINGVAR(tSpaceYColon)
|
||||
|
@ -134,13 +135,16 @@ FSTRINGVAR(tEEPROMUpdated)
|
|||
FSTRINGVAR(tFilamentSlipping)
|
||||
FSTRINGVAR(tPauseCommunication)
|
||||
FSTRINGVAR(tContinueCommunication)
|
||||
#if NONLINEAR_SYSTEM
|
||||
FSTRINGVAR(tInvalidDeltaCoordinate)
|
||||
FSTRINGVAR(tDBGDeltaNoMoveinDSegment)
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
FSTRINGVAR(tMeasurementReset)
|
||||
FSTRINGVAR(tMeasureDeltaSteps)
|
||||
FSTRINGVAR(tMeasureDelta)
|
||||
FSTRINGVAR(tMeasureOriginReset)
|
||||
FSTRINGVAR(tMeasurementAbortedOrigin)
|
||||
FSTRINGVAR(tInvalidDeltaCoordinate)
|
||||
FSTRINGVAR(tLevelingCalc)
|
||||
FSTRINGVAR(tTower1)
|
||||
FSTRINGVAR(tTower2)
|
||||
|
@ -154,12 +158,9 @@ FSTRINGVAR(tDeltaRadiusCorrectionC)
|
|||
FSTRINGVAR(tDeltaDiagonalCorrectionA)
|
||||
FSTRINGVAR(tDeltaDiagonalCorrectionB)
|
||||
FSTRINGVAR(tDeltaDiagonalCorrectionC)
|
||||
FSTRINGVAR(tDBGDeltaNoMoveinDSegment)
|
||||
FSTRINGVAR(tEPRDeltaMaxRadius)
|
||||
#endif // DRIVE_SYSTEM
|
||||
#if DRIVE_SYSTEM==TUGA
|
||||
FSTRINGVAR(tInvalidDeltaCoordinate)
|
||||
FSTRINGVAR(tDBGDeltaNoMoveinDSegment)
|
||||
FSTRINGVAR(tEPRDiagonalRodLength)
|
||||
#endif
|
||||
#ifdef DEBUG_GENERIC
|
||||
|
@ -319,8 +320,6 @@ FSTRINGVAR(tEPRYTravelAcceleration)
|
|||
#else
|
||||
FSTRINGVAR(tEPRDiagonalRodLength)
|
||||
FSTRINGVAR(tEPRHorizontalRadius)
|
||||
FSTRINGVAR(tEPRSegmentsPerSecondPrint)
|
||||
FSTRINGVAR(tEPRSegmentsPerSecondTravel)
|
||||
FSTRINGVAR(tEPRTowerXOffset)
|
||||
FSTRINGVAR(tEPRTowerYOffset)
|
||||
FSTRINGVAR(tEPRTowerZOffset)
|
||||
|
@ -405,12 +404,16 @@ FSTRINGVAR(tExtrDot)
|
|||
FSTRINGVAR(tMCPEpromSettings)
|
||||
FSTRINGVAR(tMCPCurrentSettings)
|
||||
#endif
|
||||
FSTRINGVAR(tPrinterModeFFF)
|
||||
FSTRINGVAR(tPrinterModeLaser)
|
||||
FSTRINGVAR(tPrinterModeCNC)
|
||||
FSTRINGVAR(tPrinterModeFFF)
|
||||
FSTRINGVAR(tPrinterModeLaser)
|
||||
FSTRINGVAR(tPrinterModeCNC)
|
||||
#ifdef STARTUP_GCODE
|
||||
FSTRINGVAR(tStartupGCode)
|
||||
#endif
|
||||
#if NONLINEAR_SYSTEM
|
||||
FSTRINGVAR(tEPRSegmentsPerSecondPrint)
|
||||
FSTRINGVAR(tEPRSegmentsPerSecondTravel)
|
||||
#endif
|
||||
|
||||
static void config(FSTRINGPARAM(text));
|
||||
static void config(FSTRINGPARAM(text),int value);
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
#define FAN_PIN -1
|
||||
#undef FAN_BOARD_PIN
|
||||
#define FAN_BOARD_PIN -1
|
||||
#define BOARD_FAN_SPEED 255
|
||||
#define FAN_THERMO_PIN -1
|
||||
#define FAN_THERMO_MIN_PWM 128
|
||||
#define FAN_THERMO_MAX_PWM 255
|
||||
|
@ -56,8 +57,8 @@
|
|||
#define FAN_THERMO_THERMISTOR_TYPE 1
|
||||
|
||||
//#define EXTERNALSERIAL use Arduino serial library instead of build in. Requires more ram, has only 63 byte input buffer.
|
||||
// Uncomment the following line if you are using arduino compatible firmware made for Arduino version earlier then 1.0
|
||||
// If it is incompatible you will get compiler errors about write functions not beeing compatible!
|
||||
// Uncomment the following line if you are using Arduino compatible firmware made for Arduino version earlier then 1.0
|
||||
// If it is incompatible you will get compiler errors about write functions not being compatible!
|
||||
//#define COMPAT_PRE1
|
||||
#define BLUETOOTH_SERIAL -1
|
||||
#define BLUETOOTH_BAUD 115200
|
||||
|
@ -76,8 +77,9 @@
|
|||
#define RETRACT_ON_PAUSE 2
|
||||
#define PAUSE_START_COMMANDS ""
|
||||
#define PAUSE_END_COMMANDS ""
|
||||
#define EXT0_X_OFFSET 0
|
||||
#define EXT0_Y_OFFSET 2800
|
||||
#define SHARED_EXTRUDER_HEATER 0
|
||||
#define EXT0_X_OFFSET -2800
|
||||
#define EXT0_Y_OFFSET 0
|
||||
#define EXT0_Z_OFFSET 0
|
||||
#define EXT0_STEPS_PER_MM 1000
|
||||
#define EXT0_TEMPSENSOR_TYPE 8
|
||||
|
@ -88,6 +90,11 @@
|
|||
#define EXT0_INVERSE 0
|
||||
#define EXT0_ENABLE_PIN ORIG_E0_ENABLE_PIN
|
||||
#define EXT0_ENABLE_ON 0
|
||||
#define EXT0_MIRROR_STEPPER 0
|
||||
#define EXT0_STEP2_PIN ORIG_E0_STEP_PIN
|
||||
#define EXT0_DIR2_PIN ORIG_E0_DIR_PIN
|
||||
#define EXT0_INVERSE2 0
|
||||
#define EXT0_ENABLE2_PIN ORIG_E0_ENABLE_PIN
|
||||
#define EXT0_MAX_FEEDRATE 50
|
||||
#define EXT0_MAX_START_FEEDRATE 20
|
||||
#define EXT0_MAX_ACCELERATION 5000
|
||||
|
@ -111,8 +118,8 @@
|
|||
#define EXT0_DECOUPLE_TEST_PERIOD 12000
|
||||
#define EXT0_JAM_PIN -1
|
||||
#define EXT0_JAM_PULLUP 0
|
||||
#define EXT1_X_OFFSET 0
|
||||
#define EXT1_Y_OFFSET -2800
|
||||
#define EXT1_X_OFFSET 2800
|
||||
#define EXT1_Y_OFFSET 0
|
||||
#define EXT1_Z_OFFSET 0
|
||||
#define EXT1_STEPS_PER_MM 1000
|
||||
#define EXT1_TEMPSENSOR_TYPE 8
|
||||
|
@ -123,6 +130,11 @@
|
|||
#define EXT1_INVERSE 0
|
||||
#define EXT1_ENABLE_PIN ORIG_E1_ENABLE_PIN
|
||||
#define EXT1_ENABLE_ON 0
|
||||
#define EXT1_MIRROR_STEPPER 0
|
||||
#define EXT1_STEP2_PIN ORIG_E1_STEP_PIN
|
||||
#define EXT1_DIR2_PIN ORIG_E1_DIR_PIN
|
||||
#define EXT1_INVERSE2 0
|
||||
#define EXT1_ENABLE2_PIN ORIG_E1_ENABLE_PIN
|
||||
#define EXT1_MAX_FEEDRATE 50
|
||||
#define EXT1_MAX_START_FEEDRATE 20
|
||||
#define EXT1_MAX_ACCELERATION 5000
|
||||
|
@ -170,10 +182,10 @@
|
|||
#define JAM_ACTION 0
|
||||
|
||||
#define RETRACT_DURING_HEATUP true
|
||||
#define PID_CONTROL_RANGE 20
|
||||
#define PID_CONTROL_RANGE 10
|
||||
#define SKIP_M109_IF_WITHIN 2
|
||||
#define SCALE_PID_TO_MAX 0
|
||||
#define TEMP_HYSTERESIS 0
|
||||
#define TEMP_HYSTERESIS 3
|
||||
#define EXTRUDE_MAXLENGTH 500
|
||||
#define NUM_TEMPS_USERTHERMISTOR0 0
|
||||
#define USER_THERMISTORTABLE0 {}
|
||||
|
@ -259,8 +271,8 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
// ################ Endstop configuration #####################
|
||||
|
||||
#define ENDSTOP_PULLUP_X_MIN true
|
||||
#define ENDSTOP_X_MIN_INVERTING false
|
||||
#define MIN_HARDWARE_ENDSTOP_X false
|
||||
#define ENDSTOP_X_MIN_INVERTING true
|
||||
#define MIN_HARDWARE_ENDSTOP_X true
|
||||
#define ENDSTOP_PULLUP_Y_MIN true
|
||||
#define ENDSTOP_Y_MIN_INVERTING true
|
||||
#define MIN_HARDWARE_ENDSTOP_Y true
|
||||
|
@ -268,8 +280,8 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
#define ENDSTOP_Z_MIN_INVERTING false
|
||||
#define MIN_HARDWARE_ENDSTOP_Z false
|
||||
#define ENDSTOP_PULLUP_X_MAX true
|
||||
#define ENDSTOP_X_MAX_INVERTING true
|
||||
#define MAX_HARDWARE_ENDSTOP_X true
|
||||
#define ENDSTOP_X_MAX_INVERTING false
|
||||
#define MAX_HARDWARE_ENDSTOP_X false
|
||||
#define ENDSTOP_PULLUP_Y_MAX true
|
||||
#define ENDSTOP_Y_MAX_INVERTING false
|
||||
#define MAX_HARDWARE_ENDSTOP_Y false
|
||||
|
@ -278,10 +290,10 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
#define MAX_HARDWARE_ENDSTOP_Z true
|
||||
#define max_software_endstop_r true
|
||||
|
||||
#define min_software_endstop_x true
|
||||
#define min_software_endstop_x false
|
||||
#define min_software_endstop_y false
|
||||
#define min_software_endstop_z true
|
||||
#define max_software_endstop_x false
|
||||
#define max_software_endstop_x true
|
||||
#define max_software_endstop_y true
|
||||
#define max_software_endstop_z false
|
||||
#define ENDSTOP_X_BACK_MOVE 5
|
||||
|
@ -290,8 +302,8 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
#define ENDSTOP_X_RETEST_REDUCTION_FACTOR 3
|
||||
#define ENDSTOP_Y_RETEST_REDUCTION_FACTOR 3
|
||||
#define ENDSTOP_Z_RETEST_REDUCTION_FACTOR 3
|
||||
#define ENDSTOP_X_BACK_ON_HOME 10
|
||||
#define ENDSTOP_Y_BACK_ON_HOME 1
|
||||
#define ENDSTOP_X_BACK_ON_HOME 0
|
||||
#define ENDSTOP_Y_BACK_ON_HOME 0
|
||||
#define ENDSTOP_Z_BACK_ON_HOME 0
|
||||
#define ALWAYS_CHECK_ENDSTOPS 0
|
||||
|
||||
|
@ -307,7 +319,7 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
#define INVERT_X_DIR 0
|
||||
#define INVERT_Y_DIR 0
|
||||
#define INVERT_Z_DIR 0
|
||||
#define X_HOME_DIR 1
|
||||
#define X_HOME_DIR -1
|
||||
#define Y_HOME_DIR -1
|
||||
#define Z_HOME_DIR 1
|
||||
#define X_MAX_LENGTH 155
|
||||
|
@ -333,7 +345,7 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
// ## Movement settings ##
|
||||
// ##########################################################################################
|
||||
|
||||
#define FEATURE_BABYSTEPPING 1
|
||||
#define FEATURE_BABYSTEPPING 0
|
||||
#define BABYSTEP_MULTIPLICATOR 1
|
||||
|
||||
#define DELTA_SEGMENTS_PER_SECOND_PRINT 180 // Move accurate setting for print moves
|
||||
|
@ -381,6 +393,8 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
#define PRINTLINE_CACHE_SIZE 16
|
||||
#define MOVE_CACHE_LOW 10
|
||||
#define LOW_TICKS_PER_MOVE 250000
|
||||
#define EXTRUDER_SWITCH_XY_SPEED 100
|
||||
#define DUAL_X_AXIS 0
|
||||
#define FEATURE_TWO_XSTEPPER 0
|
||||
#define X2_STEP_PIN ORIG_E1_STEP_PIN
|
||||
#define X2_DIR_PIN ORIG_E1_DIR_PIN
|
||||
|
@ -408,10 +422,10 @@ It also can add a delay to wait for spindle to run on full speed.
|
|||
#define ENABLE_POWER_ON_STARTUP 1
|
||||
#define POWER_INVERTING 0
|
||||
#define KILL_METHOD 1
|
||||
#define ACK_WITH_LINENUMBER 1
|
||||
#define ACK_WITH_LINENUMBER 0
|
||||
#define WAITING_IDENTIFIER "wait"
|
||||
#define ECHO_ON_EXECUTE 1
|
||||
#define EEPROM_MODE 2
|
||||
#define EEPROM_MODE 0
|
||||
#undef PS_ON_PIN
|
||||
#define PS_ON_PIN ORIG_PS_ON_PIN
|
||||
#define JSON_OUTPUT 0
|
||||
|
@ -442,28 +456,30 @@ WARNING: Servos can draw a considerable amount of current. Make sure your system
|
|||
#define Z_PROBE_Z_OFFSET_MODE 0
|
||||
#define UI_BED_COATING 1
|
||||
#define FEATURE_Z_PROBE 1
|
||||
#define Z_PROBE_BED_DISTANCE 10
|
||||
#define Z_PROBE_BED_DISTANCE 3
|
||||
#define Z_PROBE_PIN ORIG_Z_MIN_PIN
|
||||
#define Z_PROBE_PULLUP 1
|
||||
#define Z_PROBE_ON_HIGH 1
|
||||
#define Z_PROBE_X_OFFSET 6.4
|
||||
#define Z_PROBE_Y_OFFSET 0
|
||||
#define Z_PROBE_WAIT_BEFORE_TEST 0
|
||||
#define Z_PROBE_SPEED 100
|
||||
#define Z_PROBE_XY_SPEED 150
|
||||
#define Z_PROBE_SWITCHING_DISTANCE 1
|
||||
#define Z_PROBE_SPEED 30
|
||||
#define Z_PROBE_XY_SPEED 250
|
||||
#define Z_PROBE_SWITCHING_DISTANCE 0.3
|
||||
#define Z_PROBE_REPETITIONS 1
|
||||
#define Z_PROBE_HEIGHT 6.9
|
||||
#define Z_PROBE_HEIGHT 7.2
|
||||
#define Z_PROBE_START_SCRIPT ""
|
||||
#define Z_PROBE_FINISHED_SCRIPT ""
|
||||
#define Z_PROBE_REQUIRES_HEATING 0
|
||||
#define Z_PROBE_MIN_TEMPERATURE 150
|
||||
#define FEATURE_AUTOLEVEL 1
|
||||
#define Z_PROBE_X1 5
|
||||
#define Z_PROBE_Y1 5
|
||||
#define Z_PROBE_X2 150
|
||||
#define Z_PROBE_Y2 5
|
||||
#define Z_PROBE_X3 150
|
||||
#define Z_PROBE_X3 5
|
||||
#define Z_PROBE_Y3 150
|
||||
#define BED_LEVELING_METHOD 0
|
||||
#define BED_LEVELING_METHOD 1
|
||||
#define BED_CORRECTION_METHOD 0
|
||||
#define BED_LEVELING_GRID_SIZE 5
|
||||
#define BED_LEVELING_REPETITIONS 5
|
||||
|
@ -490,23 +506,25 @@ WARNING: Servos can draw a considerable amount of current. Make sure your system
|
|||
#define SD_EXTENDED_DIR 1 /** Show extended directory including file length. Don't use this with Pronterface! */
|
||||
#define SD_RUN_ON_STOP ""
|
||||
#define SD_STOP_HEATER_AND_MOTORS_ON_STOP 1
|
||||
#define ARC_SUPPORT 1
|
||||
#define ARC_SUPPORT 0
|
||||
#define FEATURE_MEMORY_POSITION 0
|
||||
#define FEATURE_CHECKSUM_FORCED 0
|
||||
#define FEATURE_FAN_CONTROL 0
|
||||
#define FEATURE_FAN2_CONTROL 0
|
||||
#define FEATURE_CONTROLLER 0
|
||||
#define ADC_KEYPAD_PIN -1
|
||||
#define LANGUAGE_EN_ACTIVE 1
|
||||
#define LANGUAGE_DE_ACTIVE 1
|
||||
#define LANGUAGE_NL_ACTIVE 1
|
||||
#define LANGUAGE_PT_ACTIVE 1
|
||||
#define LANGUAGE_IT_ACTIVE 1
|
||||
#define LANGUAGE_ES_ACTIVE 1
|
||||
#define LANGUAGE_SE_ACTIVE 1
|
||||
#define LANGUAGE_FR_ACTIVE 1
|
||||
#define LANGUAGE_CZ_ACTIVE 1
|
||||
#define LANGUAGE_PL_ACTIVE 1
|
||||
#define LANGUAGE_TR_ACTIVE 1
|
||||
#define LANGUAGE_DE_ACTIVE 0
|
||||
#define LANGUAGE_NL_ACTIVE 0
|
||||
#define LANGUAGE_PT_ACTIVE 0
|
||||
#define LANGUAGE_IT_ACTIVE 0
|
||||
#define LANGUAGE_ES_ACTIVE 0
|
||||
#define LANGUAGE_FI_ACTIVE 0
|
||||
#define LANGUAGE_SE_ACTIVE 0
|
||||
#define LANGUAGE_FR_ACTIVE 0
|
||||
#define LANGUAGE_CZ_ACTIVE 0
|
||||
#define LANGUAGE_PL_ACTIVE 0
|
||||
#define LANGUAGE_TR_ACTIVE 0
|
||||
#define UI_PRINTER_NAME "RepRap"
|
||||
#define UI_PRINTER_COMPANY "Home made"
|
||||
#define UI_PAGES_DURATION 4000
|
||||
|
@ -564,10 +582,10 @@ Values must be in range 1..255
|
|||
"xStepsPerMM": 200,
|
||||
"yStepsPerMM": 200,
|
||||
"zStepsPerMM": 200,
|
||||
"xInvert": 0,
|
||||
"xInvert": "0",
|
||||
"xInvertEnable": 0,
|
||||
"eepromMode": 2,
|
||||
"yInvert": 0,
|
||||
"eepromMode": 0,
|
||||
"yInvert": "0",
|
||||
"yInvertEnable": 0,
|
||||
"zInvert": 0,
|
||||
"zInvertEnable": 0,
|
||||
|
@ -600,11 +618,11 @@ Values must be in range 1..255
|
|||
"coolerSpeed": 255,
|
||||
"selectCommands": "",
|
||||
"deselectCommands": "",
|
||||
"xOffset": 0,
|
||||
"yOffset": 14,
|
||||
"xOffset": -14,
|
||||
"yOffset": null,
|
||||
"zOffset": 0,
|
||||
"xOffsetSteps": 0,
|
||||
"yOffsetSteps": 2800,
|
||||
"xOffsetSteps": -2800,
|
||||
"yOffsetSteps": 0,
|
||||
"zOffsetSteps": 0,
|
||||
"stepper": {
|
||||
"name": "Extruder 0",
|
||||
|
@ -615,7 +633,15 @@ Values must be in range 1..255
|
|||
"advanceBacklashSteps": 0,
|
||||
"decoupleTestPeriod": 12,
|
||||
"jamPin": -1,
|
||||
"jamPullup": "0"
|
||||
"jamPullup": "0",
|
||||
"mirror": "0",
|
||||
"invert2": "0",
|
||||
"stepper2": {
|
||||
"name": "Extruder 0",
|
||||
"step": "ORIG_E0_STEP_PIN",
|
||||
"dir": "ORIG_E0_DIR_PIN",
|
||||
"enable": "ORIG_E0_ENABLE_PIN"
|
||||
}
|
||||
},
|
||||
{
|
||||
"id": 1,
|
||||
|
@ -645,11 +671,11 @@ Values must be in range 1..255
|
|||
"coolerSpeed": 255,
|
||||
"selectCommands": "",
|
||||
"deselectCommands": "",
|
||||
"xOffset": 0,
|
||||
"yOffset": -14,
|
||||
"xOffset": 14,
|
||||
"yOffset": 0,
|
||||
"zOffset": 0,
|
||||
"xOffsetSteps": 0,
|
||||
"yOffsetSteps": -2800,
|
||||
"xOffsetSteps": 2800,
|
||||
"yOffsetSteps": 0,
|
||||
"zOffsetSteps": 0,
|
||||
"stepper": {
|
||||
"name": "Extruder 1",
|
||||
|
@ -660,15 +686,23 @@ Values must be in range 1..255
|
|||
"advanceBacklashSteps": 0,
|
||||
"decoupleTestPeriod": 12,
|
||||
"jamPin": -1,
|
||||
"jamPullup": "0"
|
||||
"jamPullup": "0",
|
||||
"mirror": "0",
|
||||
"invert2": "0",
|
||||
"stepper2": {
|
||||
"name": "Extruder 1",
|
||||
"step": "ORIG_E1_STEP_PIN",
|
||||
"dir": "ORIG_E1_DIR_PIN",
|
||||
"enable": "ORIG_E1_ENABLE_PIN"
|
||||
}
|
||||
}
|
||||
],
|
||||
"uiLanguage": 0,
|
||||
"uiController": 0,
|
||||
"xMinEndstop": 0,
|
||||
"xMinEndstop": 1,
|
||||
"yMinEndstop": 1,
|
||||
"zMinEndstop": 0,
|
||||
"xMaxEndstop": 1,
|
||||
"xMaxEndstop": 0,
|
||||
"yMaxEndstop": 0,
|
||||
"zMaxEndstop": 1,
|
||||
"motherboard": 33,
|
||||
|
@ -720,11 +754,11 @@ Values must be in range 1..255
|
|||
"disableY": "0",
|
||||
"disableZ": "0",
|
||||
"disableE": "0",
|
||||
"xHomeDir": "1",
|
||||
"xHomeDir": "-1",
|
||||
"yHomeDir": "-1",
|
||||
"zHomeDir": "1",
|
||||
"xEndstopBack": 10,
|
||||
"yEndstopBack": 1,
|
||||
"xEndstopBack": 0,
|
||||
"yEndstopBack": 0,
|
||||
"zEndstopBack": 0,
|
||||
"deltaSegmentsPerSecondPrint": 180,
|
||||
"deltaSegmentsPerSecondTravel": 70,
|
||||
|
@ -758,7 +792,7 @@ Values must be in range 1..255
|
|||
"enablePowerOnStartup": "1",
|
||||
"echoOnExecute": "1",
|
||||
"sendWaits": "1",
|
||||
"ackWithLineNumber": "1",
|
||||
"ackWithLineNumber": "0",
|
||||
"killMethod": 1,
|
||||
"useAdvance": "0",
|
||||
"useQuadraticAdvance": "0",
|
||||
|
@ -883,15 +917,15 @@ Values must be in range 1..255
|
|||
"temps": [],
|
||||
"numEntries": 0
|
||||
},
|
||||
"tempHysteresis": 0,
|
||||
"pidControlRange": 20,
|
||||
"tempHysteresis": 3,
|
||||
"pidControlRange": 10,
|
||||
"skipM109Within": 2,
|
||||
"extruderFanCoolTemp": 50,
|
||||
"minTemp": 150,
|
||||
"maxTemp": 285,
|
||||
"minDefectTemp": -10,
|
||||
"maxDefectTemp": 290,
|
||||
"arcSupport": "1",
|
||||
"arcSupport": "0",
|
||||
"featureMemoryPositionWatchdog": "0",
|
||||
"forceChecksum": "0",
|
||||
"sdExtendedDir": "1",
|
||||
|
@ -906,17 +940,17 @@ Values must be in range 1..255
|
|||
"fanThermoMaxTemp": 60,
|
||||
"fanThermoThermistorPin": -1,
|
||||
"fanThermoThermistorType": 1,
|
||||
"scalePidToMax": 0,
|
||||
"scalePidToMax": "0",
|
||||
"zProbePin": "ORIG_Z_MIN_PIN",
|
||||
"zProbeBedDistance": 10,
|
||||
"zProbeBedDistance": 3,
|
||||
"zProbePullup": "1",
|
||||
"zProbeOnHigh": "1",
|
||||
"zProbeXOffset": 6.4,
|
||||
"zProbeYOffset": 0,
|
||||
"zProbeWaitBeforeTest": "0",
|
||||
"zProbeSpeed": 100,
|
||||
"zProbeXYSpeed": 150,
|
||||
"zProbeHeight": 6.9,
|
||||
"zProbeSpeed": 30,
|
||||
"zProbeXYSpeed": 250,
|
||||
"zProbeHeight": 7.2,
|
||||
"zProbeStartScript": "",
|
||||
"zProbeFinishedScript": "",
|
||||
"featureAutolevel": "1",
|
||||
|
@ -924,9 +958,9 @@ Values must be in range 1..255
|
|||
"zProbeY1": 5,
|
||||
"zProbeX2": 150,
|
||||
"zProbeY2": 5,
|
||||
"zProbeX3": 150,
|
||||
"zProbeX3": 5,
|
||||
"zProbeY3": 150,
|
||||
"zProbeSwitchingDistance": 1,
|
||||
"zProbeSwitchingDistance": 0.3,
|
||||
"zProbeRepetitions": 1,
|
||||
"sdSupport": "0",
|
||||
"sdCardDetectPin": -1,
|
||||
|
@ -947,7 +981,7 @@ Values must be in range 1..255
|
|||
"deltaHomeOnPower": "0",
|
||||
"fanBoardPin": -1,
|
||||
"heaterPWMSpeed": 0,
|
||||
"featureBabystepping": "1",
|
||||
"featureBabystepping": "0",
|
||||
"babystepMultiplicator": 1,
|
||||
"pdmForHeater": "0",
|
||||
"pdmForCooler": "0",
|
||||
|
@ -1085,16 +1119,17 @@ Values must be in range 1..255
|
|||
"zProbeZOffset": 0,
|
||||
"uiBedCoating": "1",
|
||||
"langEN": "1",
|
||||
"langDE": "1",
|
||||
"langNL": "1",
|
||||
"langPT": "1",
|
||||
"langIT": "1",
|
||||
"langES": "1",
|
||||
"langSE": "1",
|
||||
"langFR": "1",
|
||||
"langCZ": "1",
|
||||
"langPL": "1",
|
||||
"langTR": "1",
|
||||
"langDE": "0",
|
||||
"langNL": "0",
|
||||
"langPT": "0",
|
||||
"langIT": "0",
|
||||
"langES": "0",
|
||||
"langFI": "0",
|
||||
"langSE": "0",
|
||||
"langFR": "0",
|
||||
"langCZ": "0",
|
||||
"langPL": "0",
|
||||
"langTR": "0",
|
||||
"interpolateAccelerationWithZ": 0,
|
||||
"accelerationFactorTop": 100,
|
||||
"bendingCorrectionA": 0,
|
||||
|
@ -1114,7 +1149,7 @@ Values must be in range 1..255
|
|||
"cncDirectionCW": "1",
|
||||
"startupGCode": "",
|
||||
"jsonOutput": "0",
|
||||
"bedLevelingMethod": 0,
|
||||
"bedLevelingMethod": 1,
|
||||
"bedCorrectionMethod": 0,
|
||||
"bedLevelingGridSize": 5,
|
||||
"bedLevelingRepetitions": 5,
|
||||
|
@ -1124,6 +1159,13 @@ Values must be in range 1..255
|
|||
"bedMotor2Y": 0,
|
||||
"bedMotor3X": 100,
|
||||
"bedMotor3Y": 200,
|
||||
"zProbeRequiresHeating": "0",
|
||||
"zProbeMinTemperature": 150,
|
||||
"adcKeypadPin": -1,
|
||||
"sharedExtruderHeater": "0",
|
||||
"extruderSwitchXYSpeed": 100,
|
||||
"dualXAxis": "0",
|
||||
"boardFanSpeed": 255,
|
||||
"hasMAX6675": false,
|
||||
"hasMAX31855": false,
|
||||
"hasGeneric1": false,
|
||||
|
@ -1133,7 +1175,7 @@ Values must be in range 1..255
|
|||
"hasUser1": false,
|
||||
"hasUser2": false,
|
||||
"numExtruder": 2,
|
||||
"version": 92.8,
|
||||
"version": 92.9,
|
||||
"primaryPortName": ""
|
||||
}
|
||||
========== End configuration string ==========
|
||||
|
|
|
@ -1,215 +1,215 @@
|
|||
#include "Repetier.h"
|
||||
|
||||
#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0
|
||||
MOTOR_DRIVER_1(motorDriver1);
|
||||
#if NUM_MOTOR_DRIVERS > 1
|
||||
MOTOR_DRIVER_2(motorDriver2);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 2
|
||||
MOTOR_DRIVER_3(motorDriver3);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 3
|
||||
MOTOR_DRIVER_4(motorDriver4);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 4
|
||||
MOTOR_DRIVER_5(motorDriver5);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 5
|
||||
MOTOR_DRIVER_6(motorDriver6);
|
||||
#endif
|
||||
|
||||
MotorDriverInterface *motorDrivers[NUM_MOTOR_DRIVERS] =
|
||||
{
|
||||
&motorDriver1
|
||||
#if NUM_MOTOR_DRIVERS > 1
|
||||
, &motorDriver2
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 2
|
||||
, &motorDriver3
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 3
|
||||
, &motorDriver4
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 4
|
||||
, &motorDriver5
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 5
|
||||
, &motorDriver6
|
||||
#endif
|
||||
};
|
||||
|
||||
MotorDriverInterface *getMotorDriver(int idx)
|
||||
{
|
||||
return motorDrivers[idx];
|
||||
}
|
||||
|
||||
/**
|
||||
Run motor P until it is at position X
|
||||
*/
|
||||
void commandG201(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasX()) return;
|
||||
motorDrivers[id]->gotoPosition(code.X);
|
||||
}
|
||||
|
||||
//G202 P<motorId> X<setpos> - Mark current position as X
|
||||
void commandG202(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasX()) return;
|
||||
motorDrivers[id]->setCurrentAs(code.X);
|
||||
}
|
||||
//G203 P<motorId> - Report current motor position
|
||||
void commandG203(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
Com::printF(PSTR("Motor"),id);
|
||||
Com::printFLN(PSTR("Pos:"),motorDrivers[id]->getPosition());
|
||||
}
|
||||
//G204 P<motorId> S<0/1> - Enable/disable motor
|
||||
void commandG204(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasS()) return;
|
||||
if(code.S)
|
||||
motorDrivers[id]->enable();
|
||||
else
|
||||
motorDrivers[id]->disable();
|
||||
}
|
||||
|
||||
void disableAllMotorDrivers()
|
||||
{
|
||||
for(int i = 0; i < NUM_MOTOR_DRIVERS; i++)
|
||||
motorDrivers[i]->disable();
|
||||
}
|
||||
void initializeAllMotorDrivers()
|
||||
{
|
||||
for(int i = 0; i < NUM_MOTOR_DRIVERS; i++)
|
||||
motorDrivers[i]->initialize();
|
||||
}
|
||||
|
||||
#endif // NUM_MOTOR_DRIVERS
|
||||
|
||||
#if defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
uint8_t LaserDriver::intensity = 255; // Intensity to use for next move queued if we want lasers. This is NOT the current value!
|
||||
bool LaserDriver::laserOn = false;
|
||||
void LaserDriver::initialize()
|
||||
{
|
||||
if(EVENT_INITALIZE_LASER)
|
||||
{
|
||||
#if LASER_PIN > -1
|
||||
SET_OUTPUT(LASER_PIN);
|
||||
#endif
|
||||
}
|
||||
changeIntensity(0);
|
||||
}
|
||||
void LaserDriver::changeIntensity(uint8_t newIntensity)
|
||||
{
|
||||
if(EVENT_SET_LASER(newIntensity))
|
||||
{
|
||||
// Default implementation
|
||||
#if LASER_PIN > -1
|
||||
WRITE(LASER_PIN,(LASER_ON_HIGH ? newIntensity > 199 : newIntensity < 200));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif // SUPPORT_LASER
|
||||
|
||||
#if defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
/**
|
||||
The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle.
|
||||
The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables
|
||||
the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed.
|
||||
*/
|
||||
|
||||
int8_t CNCDriver::direction = 0;
|
||||
/** Initialize cnc pins. EVENT_INITALIZE_CNC should return false to prevent default initalization.*/
|
||||
void CNCDriver::initialize()
|
||||
{
|
||||
if(EVENT_INITALIZE_CNC)
|
||||
{
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
SET_OUTPUT(CNC_ENABLE_PIN);
|
||||
WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH);
|
||||
#endif
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
SET_OUTPUT(CNC_DIRECTION_PIN);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
/** Turns off spindle. For event override implement
|
||||
EVENT_SPINDLE_OFF
|
||||
returning false.
|
||||
*/
|
||||
void CNCDriver::spindleOff()
|
||||
{
|
||||
if(direction == 0) return; // already off
|
||||
if(EVENT_SPINDLE_OFF)
|
||||
{
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_DISABLE);
|
||||
direction = 0;
|
||||
}
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CW(rpm)
|
||||
*/
|
||||
void CNCDriver::spindleOnCW(int32_t rpm)
|
||||
{
|
||||
if(direction == 1)
|
||||
return;
|
||||
spindleOff();
|
||||
direction = 1;
|
||||
if(EVENT_SPINDLE_CW(rpm)) {
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
WRITE(CNC_DIRECTION_PIN, CNC_DIRECTION_CW);
|
||||
#endif
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE);
|
||||
}
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CCW(rpm)
|
||||
*/
|
||||
void CNCDriver::spindleOnCCW(int32_t rpm)
|
||||
{
|
||||
if(direction == -1)
|
||||
return;
|
||||
spindleOff();
|
||||
direction = -1;
|
||||
if(EVENT_SPINDLE_CW(rpm)) {
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
WRITE(CNC_DIRECTION_PIN, !CNC_DIRECTION_CW);
|
||||
#endif
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE);
|
||||
}
|
||||
#endif
|
||||
#include "Repetier.h"
|
||||
|
||||
#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0
|
||||
MOTOR_DRIVER_1(motorDriver1);
|
||||
#if NUM_MOTOR_DRIVERS > 1
|
||||
MOTOR_DRIVER_2(motorDriver2);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 2
|
||||
MOTOR_DRIVER_3(motorDriver3);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 3
|
||||
MOTOR_DRIVER_4(motorDriver4);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 4
|
||||
MOTOR_DRIVER_5(motorDriver5);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 5
|
||||
MOTOR_DRIVER_6(motorDriver6);
|
||||
#endif
|
||||
|
||||
MotorDriverInterface *motorDrivers[NUM_MOTOR_DRIVERS] =
|
||||
{
|
||||
&motorDriver1
|
||||
#if NUM_MOTOR_DRIVERS > 1
|
||||
, &motorDriver2
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 2
|
||||
, &motorDriver3
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 3
|
||||
, &motorDriver4
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 4
|
||||
, &motorDriver5
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 5
|
||||
, &motorDriver6
|
||||
#endif
|
||||
};
|
||||
|
||||
MotorDriverInterface *getMotorDriver(int idx)
|
||||
{
|
||||
return motorDrivers[idx];
|
||||
}
|
||||
|
||||
/**
|
||||
Run motor P until it is at position X
|
||||
*/
|
||||
void commandG201(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasX()) return;
|
||||
motorDrivers[id]->gotoPosition(code.X);
|
||||
}
|
||||
|
||||
//G202 P<motorId> X<setpos> - Mark current position as X
|
||||
void commandG202(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasX()) return;
|
||||
motorDrivers[id]->setCurrentAs(code.X);
|
||||
}
|
||||
//G203 P<motorId> - Report current motor position
|
||||
void commandG203(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
Com::printF(PSTR("Motor"),id);
|
||||
Com::printFLN(PSTR("Pos:"),motorDrivers[id]->getPosition());
|
||||
}
|
||||
//G204 P<motorId> S<0/1> - Enable/disable motor
|
||||
void commandG204(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasS()) return;
|
||||
if(code.S)
|
||||
motorDrivers[id]->enable();
|
||||
else
|
||||
motorDrivers[id]->disable();
|
||||
}
|
||||
|
||||
void disableAllMotorDrivers()
|
||||
{
|
||||
for(int i = 0; i < NUM_MOTOR_DRIVERS; i++)
|
||||
motorDrivers[i]->disable();
|
||||
}
|
||||
void initializeAllMotorDrivers()
|
||||
{
|
||||
for(int i = 0; i < NUM_MOTOR_DRIVERS; i++)
|
||||
motorDrivers[i]->initialize();
|
||||
}
|
||||
|
||||
#endif // NUM_MOTOR_DRIVERS
|
||||
|
||||
#if defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
uint8_t LaserDriver::intensity = 255; // Intensity to use for next move queued if we want lasers. This is NOT the current value!
|
||||
bool LaserDriver::laserOn = false;
|
||||
void LaserDriver::initialize()
|
||||
{
|
||||
if(EVENT_INITALIZE_LASER)
|
||||
{
|
||||
#if LASER_PIN > -1
|
||||
SET_OUTPUT(LASER_PIN);
|
||||
#endif
|
||||
}
|
||||
changeIntensity(0);
|
||||
}
|
||||
void LaserDriver::changeIntensity(uint8_t newIntensity)
|
||||
{
|
||||
if(EVENT_SET_LASER(newIntensity))
|
||||
{
|
||||
// Default implementation
|
||||
#if LASER_PIN > -1
|
||||
WRITE(LASER_PIN,(LASER_ON_HIGH ? newIntensity > 199 : newIntensity < 200));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif // SUPPORT_LASER
|
||||
|
||||
#if defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
/**
|
||||
The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle.
|
||||
The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables
|
||||
the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed.
|
||||
*/
|
||||
|
||||
int8_t CNCDriver::direction = 0;
|
||||
/** Initialize cnc pins. EVENT_INITALIZE_CNC should return false to prevent default initalization.*/
|
||||
void CNCDriver::initialize()
|
||||
{
|
||||
if(EVENT_INITALIZE_CNC)
|
||||
{
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
SET_OUTPUT(CNC_ENABLE_PIN);
|
||||
WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH);
|
||||
#endif
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
SET_OUTPUT(CNC_DIRECTION_PIN);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
/** Turns off spindle. For event override implement
|
||||
EVENT_SPINDLE_OFF
|
||||
returning false.
|
||||
*/
|
||||
void CNCDriver::spindleOff()
|
||||
{
|
||||
if(direction == 0) return; // already off
|
||||
if(EVENT_SPINDLE_OFF)
|
||||
{
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_DISABLE);
|
||||
direction = 0;
|
||||
}
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CW(rpm)
|
||||
*/
|
||||
void CNCDriver::spindleOnCW(int32_t rpm)
|
||||
{
|
||||
if(direction == 1)
|
||||
return;
|
||||
spindleOff();
|
||||
direction = 1;
|
||||
if(EVENT_SPINDLE_CW(rpm)) {
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
WRITE(CNC_DIRECTION_PIN, CNC_DIRECTION_CW);
|
||||
#endif
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE);
|
||||
}
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CCW(rpm)
|
||||
*/
|
||||
void CNCDriver::spindleOnCCW(int32_t rpm)
|
||||
{
|
||||
if(direction == -1)
|
||||
return;
|
||||
spindleOff();
|
||||
direction = -1;
|
||||
if(EVENT_SPINDLE_CW(rpm)) {
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
WRITE(CNC_DIRECTION_PIN, !CNC_DIRECTION_CW);
|
||||
#endif
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -20,7 +20,7 @@ the main code.
|
|||
*/
|
||||
class MotorDriverInterface
|
||||
{
|
||||
public:
|
||||
public:
|
||||
virtual void initialize() = 0;
|
||||
virtual float getPosition() = 0;
|
||||
virtual void setCurrentAs(float newPos) = 0;
|
||||
|
@ -43,12 +43,12 @@ public:
|
|||
{
|
||||
stepsPerMM = _stepsPerMM;
|
||||
delayUS = 500000 / (speed * stepsPerMM);
|
||||
}
|
||||
void initialize() {
|
||||
}
|
||||
void initialize() {
|
||||
HAL::pinMode(enablePin, OUTPUT);
|
||||
HAL::pinMode(stepPin, OUTPUT);
|
||||
HAL::pinMode(dirPin, OUTPUT);
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
}
|
||||
float getPosition()
|
||||
{
|
||||
|
@ -59,7 +59,7 @@ public:
|
|||
position = floor(newPos * stepsPerMM + 0.5f);
|
||||
}
|
||||
void gotoPosition(float newPos)
|
||||
{
|
||||
{
|
||||
enable();
|
||||
int32_t target = floor(newPos * stepsPerMM + 0.5f) - position;
|
||||
position += target;
|
||||
|
@ -74,9 +74,9 @@ public:
|
|||
HAL::delayMicroseconds(delayUS);
|
||||
HAL::digitalWrite(stepPin, LOW);
|
||||
HAL::delayMicroseconds(delayUS);
|
||||
target--;
|
||||
HAL::pingWatchdog();
|
||||
if((target & 127) == 0)
|
||||
target--;
|
||||
HAL::pingWatchdog();
|
||||
if((target & 127) == 0)
|
||||
Commands::checkForPeriodicalActions(false);
|
||||
}
|
||||
}
|
||||
|
@ -88,66 +88,66 @@ public:
|
|||
{
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
}
|
||||
};
|
||||
|
||||
#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0
|
||||
class GCode;
|
||||
};
|
||||
|
||||
#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0
|
||||
class GCode;
|
||||
extern void commandG201(GCode &code);
|
||||
extern void commandG202(GCode &code);
|
||||
extern void commandG203(GCode &code);
|
||||
extern void commandG204(GCode &code);
|
||||
extern void disableAllMotorDrivers();
|
||||
extern MotorDriverInterface *getMotorDriver(int idx);
|
||||
extern void initializeAllMotorDrivers();
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
/**
|
||||
With laser support you can exchange a extruder by a laser. A laser gets controlled by a digital pin.
|
||||
By default all intensities > 200 are always on, and lower values are always off. You can overwrite
|
||||
this with a programmed event EVENT_SET_LASER(intensity) that return false to signal the default
|
||||
implementation that it has set it's value already.
|
||||
EVENT_INITALIZE_LASER should return false to prevent default initialization.
|
||||
*/
|
||||
class LaserDriver {
|
||||
public:
|
||||
static uint8_t intensity; // Intensity to use for next move queued. This is NOT the current value!
|
||||
static bool laserOn; // Enabled by M3?
|
||||
static void initialize();
|
||||
static void changeIntensity(uint8_t newIntensity);
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
/**
|
||||
The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle.
|
||||
The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables
|
||||
the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed.
|
||||
*/
|
||||
class CNCDriver {
|
||||
public:
|
||||
static int8_t direction;
|
||||
/** Initialize cnc pins. EVENT_INITALIZE_CNC should return false to prevent default initalization.*/
|
||||
static void initialize();
|
||||
/** Turns off spindle. For event override implement
|
||||
EVENT_SPINDLE_OFF
|
||||
returning false.
|
||||
*/
|
||||
static void spindleOff();
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CW(rpm)
|
||||
*/
|
||||
static void spindleOnCW(int32_t rpm);
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CCW(rpm)
|
||||
*/
|
||||
static void spindleOnCCW(int32_t rpm);
|
||||
};
|
||||
#endif
|
||||
extern void commandG204(GCode &code);
|
||||
extern void disableAllMotorDrivers();
|
||||
extern MotorDriverInterface *getMotorDriver(int idx);
|
||||
extern void initializeAllMotorDrivers();
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
/**
|
||||
With laser support you can exchange a extruder by a laser. A laser gets controlled by a digital pin.
|
||||
By default all intensities > 200 are always on, and lower values are always off. You can overwrite
|
||||
this with a programmed event EVENT_SET_LASER(intensity) that return false to signal the default
|
||||
implementation that it has set it's value already.
|
||||
EVENT_INITALIZE_LASER should return false to prevent default initialization.
|
||||
*/
|
||||
class LaserDriver {
|
||||
public:
|
||||
static uint8_t intensity; // Intensity to use for next move queued. This is NOT the current value!
|
||||
static bool laserOn; // Enabled by M3?
|
||||
static void initialize();
|
||||
static void changeIntensity(uint8_t newIntensity);
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
/**
|
||||
The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle.
|
||||
The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables
|
||||
the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed.
|
||||
*/
|
||||
class CNCDriver {
|
||||
public:
|
||||
static int8_t direction;
|
||||
/** Initialize cnc pins. EVENT_INITALIZE_CNC should return false to prevent default initalization.*/
|
||||
static void initialize();
|
||||
/** Turns off spindle. For event override implement
|
||||
EVENT_SPINDLE_OFF
|
||||
returning false.
|
||||
*/
|
||||
static void spindleOff();
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CW(rpm)
|
||||
*/
|
||||
static void spindleOnCW(int32_t rpm);
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CCW(rpm)
|
||||
*/
|
||||
static void spindleOnCCW(int32_t rpm);
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif // DRIVERS_H_INCLUDED
|
||||
|
|
|
@ -63,7 +63,12 @@ void EEPROM::update(GCode *com)
|
|||
|
||||
void EEPROM::restoreEEPROMSettingsFromConfiguration()
|
||||
{
|
||||
// can only be done right if we also update permanent values not cached!
|
||||
#if EEPROM_MODE != 0
|
||||
EEPROM::initalizeUncached();
|
||||
uint8_t newcheck = computeChecksum();
|
||||
if(newcheck != HAL::eprGetByte(EPR_INTEGRITY_BYTE))
|
||||
HAL::eprSetByte(EPR_INTEGRITY_BYTE, newcheck);
|
||||
baudrate = BAUDRATE;
|
||||
maxInactiveTime = MAX_INACTIVE_TIME * 1000L;
|
||||
stepperInactiveTime = STEPPER_INACTIVE_TIME * 1000L;
|
||||
|
@ -106,6 +111,13 @@ void EEPROM::restoreEEPROMSettingsFromConfiguration()
|
|||
Printer::xMin = X_MIN_POS;
|
||||
Printer::yMin = Y_MIN_POS;
|
||||
Printer::zMin = Z_MIN_POS;
|
||||
#if NONLINEAR_SYSTEM
|
||||
#ifdef ROD_RADIUS
|
||||
Printer::radius0 = ROD_RADIUS;
|
||||
#else
|
||||
Printer::radius0 = 0;
|
||||
#endif
|
||||
#endif
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
Printer::backlashX = X_BACKLASH;
|
||||
Printer::backlashY = Y_BACKLASH;
|
||||
|
@ -468,11 +480,13 @@ void EEPROM::initalizeUncached()
|
|||
HAL::eprSetFloat(EPR_AXISCOMP_TANXZ,AXISCOMP_TANXZ);
|
||||
HAL::eprSetFloat(EPR_Z_PROBE_BED_DISTANCE,Z_PROBE_BED_DISTANCE);
|
||||
Printer::zBedOffset = HAL::eprGetFloat(EPR_Z_PROBE_Z_OFFSET);
|
||||
#if NONLINEAR_SYSTEM
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT,DELTA_SEGMENTS_PER_SECOND_PRINT);
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE,DELTA_SEGMENTS_PER_SECOND_MOVE);
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
HAL::eprSetFloat(EPR_DELTA_DIAGONAL_ROD_LENGTH,DELTA_DIAGONAL_ROD);
|
||||
HAL::eprSetFloat(EPR_DELTA_HORIZONTAL_RADIUS,ROD_RADIUS);
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT,DELTA_SEGMENTS_PER_SECOND_PRINT);
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE,DELTA_SEGMENTS_PER_SECOND_MOVE);
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERX_OFFSET_STEPS,DELTA_X_ENDSTOP_OFFSET_STEPS);
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERY_OFFSET_STEPS,DELTA_Y_ENDSTOP_OFFSET_STEPS);
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERZ_OFFSET_STEPS,DELTA_Z_ENDSTOP_OFFSET_STEPS);
|
||||
|
@ -526,7 +540,7 @@ void EEPROM::readDataFromEEPROM(bool includeExtruder)
|
|||
Printer::homingFeedrate[Y_AXIS] = HAL::eprGetFloat(EPR_Y_HOMING_FEEDRATE);
|
||||
Printer::homingFeedrate[Z_AXIS] = HAL::eprGetFloat(EPR_Z_HOMING_FEEDRATE);
|
||||
Printer::maxJerk = HAL::eprGetFloat(EPR_MAX_JERK);
|
||||
#if DRIVE_SYSTEM!=DELTA
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
Printer::maxZJerk = HAL::eprGetFloat(EPR_MAX_ZJERK);
|
||||
#endif
|
||||
#if RAMP_ACCELERATION
|
||||
|
@ -653,11 +667,13 @@ void EEPROM::readDataFromEEPROM(bool includeExtruder)
|
|||
}
|
||||
if(version < 4)
|
||||
{
|
||||
#if NONLINEAR_SYSTEM
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT,DELTA_SEGMENTS_PER_SECOND_PRINT);
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE,DELTA_SEGMENTS_PER_SECOND_MOVE);
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
HAL::eprSetFloat(EPR_DELTA_DIAGONAL_ROD_LENGTH,DELTA_DIAGONAL_ROD);
|
||||
HAL::eprSetFloat(EPR_DELTA_HORIZONTAL_RADIUS,ROD_RADIUS);
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT,DELTA_SEGMENTS_PER_SECOND_PRINT);
|
||||
HAL::eprSetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE,DELTA_SEGMENTS_PER_SECOND_MOVE);
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERX_OFFSET_STEPS,DELTA_X_ENDSTOP_OFFSET_STEPS);
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERY_OFFSET_STEPS,DELTA_Y_ENDSTOP_OFFSET_STEPS);
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERZ_OFFSET_STEPS,DELTA_Z_ENDSTOP_OFFSET_STEPS);
|
||||
|
@ -797,7 +813,7 @@ void EEPROM::init()
|
|||
}
|
||||
else
|
||||
{
|
||||
HAL::eprSetByte(EPR_MAGIC_BYTE,EEPROM_MODE); // Make datachange permanent
|
||||
HAL::eprSetByte(EPR_MAGIC_BYTE,EEPROM_MODE); // Make data change permanent
|
||||
initalizeUncached();
|
||||
storeDataIntoEEPROM(storedcheck != check);
|
||||
}
|
||||
|
@ -871,7 +887,10 @@ void EEPROM::writeSettings()
|
|||
writeFloat(EPR_BACKLASH_Y, Com::tEPRYBacklash);
|
||||
writeFloat(EPR_BACKLASH_Z, Com::tEPRZBacklash);
|
||||
#endif
|
||||
|
||||
#if NONLINEAR_SYSTEM
|
||||
writeInt(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE, Com::tEPRSegmentsPerSecondTravel);
|
||||
writeInt(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT, Com::tEPRSegmentsPerSecondPrint);
|
||||
#endif
|
||||
#if RAMP_ACCELERATION
|
||||
//epr_out_float(EPR_X_MAX_START_SPEED,PSTR("X-axis start speed [mm/s]"));
|
||||
//epr_out_float(EPR_Y_MAX_START_SPEED,PSTR("Y-axis start speed [mm/s]"));
|
||||
|
@ -888,8 +907,6 @@ void EEPROM::writeSettings()
|
|||
writeFloat(EPR_DELTA_DIAGONAL_ROD_LENGTH, Com::tEPRDiagonalRodLength);
|
||||
writeFloat(EPR_DELTA_HORIZONTAL_RADIUS, Com::tEPRHorizontalRadius);
|
||||
writeFloat(EPR_DELTA_MAX_RADIUS, Com::tEPRDeltaMaxRadius);
|
||||
writeInt(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE, Com::tEPRSegmentsPerSecondTravel);
|
||||
writeInt(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT, Com::tEPRSegmentsPerSecondPrint);
|
||||
writeInt(EPR_DELTA_TOWERX_OFFSET_STEPS, Com::tEPRTowerXOffset);
|
||||
writeInt(EPR_DELTA_TOWERY_OFFSET_STEPS, Com::tEPRTowerYOffset);
|
||||
writeInt(EPR_DELTA_TOWERZ_OFFSET_STEPS, Com::tEPRTowerZOffset);
|
||||
|
|
|
@ -195,10 +195,10 @@ public:
|
|||
static void writeSettings();
|
||||
static void update(GCode *com);
|
||||
static void updatePrinterUsage();
|
||||
static inline void setVersion(uint8_t v) {
|
||||
static inline void setVersion(uint8_t v) {
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetByte(EPR_VERSION,v);
|
||||
HAL::eprSetByte(EPR_INTEGRITY_BYTE,computeChecksum());
|
||||
HAL::eprSetByte(EPR_INTEGRITY_BYTE,computeChecksum());
|
||||
#endif
|
||||
}
|
||||
static inline uint8_t getStoredLanguage() {
|
||||
|
|
|
@ -1,84 +1,90 @@
|
|||
#ifndef EVENTS_H_INCLUDED
|
||||
#define EVENTS_H_INCLUDED
|
||||
|
||||
/*
|
||||
Event system in a nutshell:
|
||||
|
||||
All printers are different and my need additions in th eone or other place.
|
||||
It is not very convenient to add these code parts across the firmware. For this
|
||||
reason repetier-firmware uses a simple event system that comes at no cost if
|
||||
a event is not used.
|
||||
|
||||
- simple: Only one subscriber is possible
|
||||
- cost effective: Macros work as event caller. By default all macros are empty
|
||||
|
||||
How to use the system:
|
||||
|
||||
1. In Configuration.h add
|
||||
#define CUSTOM_EVENTS
|
||||
2. Add a file "CustomEvents.h" which overrides all event macros you need.
|
||||
It shoudl also include the function declarations used.
|
||||
3. Add a file "CustomEventsImpl.h" which includes all function definitions.
|
||||
Also it is named .h it will be included inside a cpp file only once.
|
||||
This is to compile only when selected and still keep ArduinoIDE happy.
|
||||
|
||||
Each of the following events describe the parameter and when it is called.
|
||||
*/
|
||||
|
||||
// Catch heating events. id is extruder id or -1 for heated bed.
|
||||
#define EVENT_WAITING_HEATER(id) {}
|
||||
#define EVENT_HEATING_FINISHED(id) {}
|
||||
|
||||
// This gets called every 0.1 second
|
||||
#define EVENT_TIMER_100MS {}
|
||||
// This gets called every 0.5 second
|
||||
#define EVENT_TIMER_500MS {}
|
||||
// Gets called on a regular basis as time allows
|
||||
#define EVENT_PERIODICAL {}
|
||||
// Gets called when kill gets called. only_steppes = true -> we only want to disable steppers, not everything.
|
||||
#define EVENT_KILL(only_steppers) {}
|
||||
// Gets called when a jam was detected.
|
||||
#define EVENT_JAM_DETECTED {}
|
||||
// Gets called everytime the jam detection signal switches. Steps are the extruder steps since last change.
|
||||
#define EVENT_JAM_SIGNAL_CHANGED(extruderId,steps) {}
|
||||
// Gets called if a heater decoupling is detected.
|
||||
#define EVENT_HEATER_DECOUPLED(id) {}
|
||||
// Gets called if a missing/shorted thermistor is detected.
|
||||
#define EVENT_HEATER_DEFECT(id) {}
|
||||
// Gets called if a action in ui.cpp okAction gets executed.
|
||||
#define EVENT_START_UI_ACTION(shortAction) {}
|
||||
// Gets called if a nextPrevius actions gets executed.
|
||||
#define EVENT_START_NEXTPREVIOUS(action,increment) {}
|
||||
|
||||
// Called to initalize laser pins. Return false to prevent default initalization.
|
||||
#define EVENT_INITALIZE_LASER true
|
||||
// Set laser to intensity level 0 = off, 255 = full. Return false if you have overridden the setting routine.
|
||||
// with true the default solution will set it as digital value.
|
||||
#define EVENT_SET_LASER(intensity) true
|
||||
|
||||
// Called to initalize cnc pins. Return false to prevent default initalization.
|
||||
#define EVENT_INITALIZE_CNC true
|
||||
// Turn off spindle
|
||||
#define EVENT_SPINDLE_OFF true
|
||||
// Turn spindle clockwise
|
||||
#define EVENT_SPINDLE_CW(rpm) true
|
||||
// Turn spindle counter clockwise
|
||||
#define EVENT_SPINDLE_CCW(rpm) true
|
||||
|
||||
// Allow adding new G and M codes. To implement it create a function
|
||||
// bool eventUnhandledGCode(GCode *com)
|
||||
// that returns true if it handled the code, otherwise false.
|
||||
// Event define would then be
|
||||
// #define EVENT_UNHANDLED_G_CODE(c) eventUnhandledGCode(c)
|
||||
#define EVENT_UNHANDLED_G_CODE(c) false
|
||||
#define EVENT_UNHANDLED_M_CODE(c) false
|
||||
|
||||
// This gets called every time the user has saved a value to eeprom
|
||||
// or any other reason why dependent values may need recomputation.
|
||||
#define EVENT_UPDATE_DERIVED {}
|
||||
|
||||
// This gets called after the basic firmware functions have initialized.
|
||||
// Use this to initalize your hardware etc.
|
||||
#define EVENT_INITIALIZE {}
|
||||
|
||||
#endif // EVENTS_H_INCLUDED
|
||||
#ifndef EVENTS_H_INCLUDED
|
||||
#define EVENTS_H_INCLUDED
|
||||
|
||||
/*
|
||||
Event system in a nutshell:
|
||||
|
||||
All printers are different and my need additions in th eone or other place.
|
||||
It is not very convenient to add these code parts across the firmware. For this
|
||||
reason repetier-firmware uses a simple event system that comes at no cost if
|
||||
a event is not used.
|
||||
|
||||
- simple: Only one subscriber is possible
|
||||
- cost effective: Macros work as event caller. By default all macros are empty
|
||||
|
||||
How to use the system:
|
||||
|
||||
1. In Configuration.h add
|
||||
#define CUSTOM_EVENTS
|
||||
2. Add a file "CustomEvents.h" which overrides all event macros you need.
|
||||
It shoudl also include the function declarations used.
|
||||
3. Add a file "CustomEventsImpl.h" which includes all function definitions.
|
||||
Also it is named .h it will be included inside a cpp file only once.
|
||||
This is to compile only when selected and still keep ArduinoIDE happy.
|
||||
|
||||
Each of the following events describe the parameter and when it is called.
|
||||
*/
|
||||
|
||||
// Catch heating events. id is extruder id or -1 for heated bed.
|
||||
#define EVENT_WAITING_HEATER(id) {}
|
||||
#define EVENT_HEATING_FINISHED(id) {}
|
||||
|
||||
// This gets called every 0.1 second
|
||||
#define EVENT_TIMER_100MS {}
|
||||
// This gets called every 0.5 second
|
||||
#define EVENT_TIMER_500MS {}
|
||||
// Gets called on a regular basis as time allows
|
||||
#define EVENT_PERIODICAL {}
|
||||
// Gets called when kill gets called. only_steppes = true -> we only want to disable steppers, not everything.
|
||||
#define EVENT_KILL(only_steppers) {}
|
||||
// Gets called when a jam was detected.
|
||||
#define EVENT_JAM_DETECTED {}
|
||||
// Gets called every time the jam detection signal switches. Steps are the extruder steps since last change.
|
||||
#define EVENT_JAM_SIGNAL_CHANGED(extruderId,steps) {}
|
||||
// Gets called if a heater decoupling is detected.
|
||||
#define EVENT_HEATER_DECOUPLED(id) {}
|
||||
// Gets called if a missing/shorted thermistor is detected.
|
||||
#define EVENT_HEATER_DEFECT(id) {}
|
||||
// Gets called if a action in ui.cpp okAction gets executed.
|
||||
#define EVENT_START_UI_ACTION(shortAction) {}
|
||||
// Gets called if a nextPrevius actions gets executed.
|
||||
#define EVENT_START_NEXTPREVIOUS(action,increment) {}
|
||||
// Gets called before a move is queued. Gives the ability to limit moves.
|
||||
#define EVENT_CONTRAIN_DESTINATION_COORDINATES
|
||||
// Gets called when a fatal error occurs and all actions should be stopped
|
||||
#define EVENT_FATAL_ERROR_OCCURED
|
||||
// Gets called after a M999 to continue from fatal errors
|
||||
#define EVENT_CONTINUE_FROM_FATAL_ERROR
|
||||
|
||||
// Called to initialize laser pins. Return false to prevent default initialization.
|
||||
#define EVENT_INITALIZE_LASER true
|
||||
// Set laser to intensity level 0 = off, 255 = full. Return false if you have overridden the setting routine.
|
||||
// with true the default solution will set it as digital value.
|
||||
#define EVENT_SET_LASER(intensity) true
|
||||
|
||||
// Called to initialize CNC pins. Return false to prevent default initialization.
|
||||
#define EVENT_INITALIZE_CNC true
|
||||
// Turn off spindle
|
||||
#define EVENT_SPINDLE_OFF true
|
||||
// Turn spindle clockwise
|
||||
#define EVENT_SPINDLE_CW(rpm) true
|
||||
// Turn spindle counter clockwise
|
||||
#define EVENT_SPINDLE_CCW(rpm) true
|
||||
|
||||
// Allow adding new G and M codes. To implement it create a function
|
||||
// bool eventUnhandledGCode(GCode *com)
|
||||
// that returns true if it handled the code, otherwise false.
|
||||
// Event define would then be
|
||||
// #define EVENT_UNHANDLED_G_CODE(c) eventUnhandledGCode(c)
|
||||
#define EVENT_UNHANDLED_G_CODE(c) false
|
||||
#define EVENT_UNHANDLED_M_CODE(c) false
|
||||
|
||||
// This gets called every time the user has saved a value to eeprom
|
||||
// or any other reason why dependent values may need recomputation.
|
||||
#define EVENT_UPDATE_DERIVED {}
|
||||
|
||||
// This gets called after the basic firmware functions have initialized.
|
||||
// Use this to initalize your hardware etc.
|
||||
#define EVENT_INITIALIZE {}
|
||||
|
||||
#endif // EVENTS_H_INCLUDED
|
||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -9,7 +9,7 @@
|
|||
//#endif
|
||||
|
||||
// Updates the temperature of all extruders and heated bed if it's time.
|
||||
// Toggels the heater power if necessary.
|
||||
// Toggles the heater power if necessary.
|
||||
extern bool reportTempsensorError(); ///< Report defect sensors
|
||||
extern uint8_t manageMonitor;
|
||||
#define HTR_OFF 0
|
||||
|
@ -25,7 +25,7 @@ extern uint8_t manageMonitor;
|
|||
#define TEMPERATURE_CONTROLLER_FLAG_JAM 32 //< Indicates a jammed filament
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_SLOWDOWN 64 //< Indicates a slowed down extruder
|
||||
|
||||
/** TemperatureController manages one heater-temperature sensore loop. You can have up to
|
||||
/** TemperatureController manages one heater-temperature sensor loop. You can have up to
|
||||
4 loops allowing pid/bang bang for up to 3 extruder and the heated bed.
|
||||
|
||||
*/
|
||||
|
@ -35,12 +35,12 @@ public:
|
|||
uint8_t pwmIndex; ///< pwm index for output control. 0-2 = Extruder, 3 = Fan, 4 = Heated Bed
|
||||
uint8_t sensorType; ///< Type of temperature sensor.
|
||||
uint8_t sensorPin; ///< Pin to read extruder temperature.
|
||||
int16_t currentTemperature; ///< Currenttemperature value read from sensor.
|
||||
int16_t targetTemperature; ///< Target temperature value in units of sensor.
|
||||
int8_t heatManager; ///< How is temperature controlled. 0 = on/off, 1 = PID-Control, 3 = dead time control
|
||||
int16_t currentTemperature; ///< Current temperature value read from sensor.
|
||||
//int16_t targetTemperature; ///< Target temperature value in units of sensor.
|
||||
float currentTemperatureC; ///< Current temperature in degC.
|
||||
float targetTemperatureC; ///< Target temperature in degC.
|
||||
uint32_t lastTemperatureUpdate; ///< Time in millis of the last temperature update.
|
||||
int8_t heatManager; ///< How is temperature controled. 0 = on/off, 1 = PID-Control, 3 = deat time control
|
||||
#if TEMP_PID
|
||||
float tempIState; ///< Temp. var. for PID computation.
|
||||
uint8_t pidDriveMax; ///< Used for windup in PID calculation.
|
||||
|
@ -77,6 +77,9 @@ public:
|
|||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL;
|
||||
}
|
||||
inline void removeErrorStates() {
|
||||
flags &= ~(TEMPERATURE_CONTROLLER_FLAG_ALARM | TEMPERATURE_CONTROLLER_FLAG_SENSDEFECT | TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED);
|
||||
}
|
||||
inline bool isDecoupleFullOrHold()
|
||||
{
|
||||
return flags & (TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL | TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD);
|
||||
|
@ -122,6 +125,7 @@ public:
|
|||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED;
|
||||
}
|
||||
static void resetAllErrorStates();
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
inline bool isJammed()
|
||||
{
|
||||
|
@ -147,7 +151,7 @@ public:
|
|||
class Extruder;
|
||||
extern Extruder extruder[];
|
||||
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
#if JAM_METHOD == 1
|
||||
#define _TEST_EXTRUDER_JAM(x,pin) {\
|
||||
uint8_t sig = READ(pin);extruder[x].jamStepsSinceLastSignal += extruder[x].jamLastDir;\
|
||||
|
@ -157,23 +161,23 @@ extern Extruder extruder[];
|
|||
} else if(abs(extruder[x].jamStepsSinceLastSignal) > JAM_ERROR_STEPS && !Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) \
|
||||
extruder[x].tempControl.setJammed(true);\
|
||||
}
|
||||
#define RESET_EXTRUDER_JAM(x,dir) extruder[x].jamLastDir = dir ? 1 : -1;
|
||||
#elif JAM_METHOD == 2
|
||||
#define RESET_EXTRUDER_JAM(x,dir) extruder[x].jamLastDir = dir ? 1 : -1;
|
||||
#elif JAM_METHOD == 2
|
||||
#define _TEST_EXTRUDER_JAM(x,pin) {\
|
||||
uint8_t sig = READ(pin);\
|
||||
if(sig){extruder[x].tempControl.setJammed(true);} else if(!Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) {extruder[x].resetJamSteps();}}
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#elif JAM_METHOD == 3
|
||||
if(sig){extruder[x].tempControl.setJammed(true);} else if(!Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) {extruder[x].resetJamSteps();}}
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#elif JAM_METHOD == 3
|
||||
#define _TEST_EXTRUDER_JAM(x,pin) {\
|
||||
uint8_t sig = !READ(pin);\
|
||||
if(sig){extruder[x].tempControl.setJammed(true);} else if(!Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) {extruder[x].resetJamSteps();}}
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#else
|
||||
#error Unknown value for JAM_METHOD
|
||||
if(sig){extruder[x].tempControl.setJammed(true);} else if(!Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) {extruder[x].resetJamSteps();}}
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#else
|
||||
#error Unknown value for JAM_METHOD
|
||||
#endif
|
||||
#define ___TEST_EXTRUDER_JAM(x,y) _TEST_EXTRUDER_JAM(x,y)
|
||||
#define __TEST_EXTRUDER_JAM(x) ___TEST_EXTRUDER_JAM(x,EXT ## x ## _JAM_PIN)
|
||||
#define TEST_EXTRUDER_JAM(x) __TEST_EXTRUDER_JAM(x)
|
||||
#define TEST_EXTRUDER_JAM(x) __TEST_EXTRUDER_JAM(x)
|
||||
#else
|
||||
#define TEST_EXTRUDER_JAM(x)
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
|
@ -202,7 +206,7 @@ public:
|
|||
#endif
|
||||
uint8_t id;
|
||||
int32_t xOffset;
|
||||
int32_t yOffset;
|
||||
int32_t yOffset;
|
||||
int32_t zOffset;
|
||||
float stepsPerMM; ///< Steps per mm.
|
||||
int8_t enablePin; ///< Pin to enable extruder stepper motor.
|
||||
|
@ -305,9 +309,9 @@ extern TemperatureController thermoController;
|
|||
#define TEMP_INT_TO_FLOAT(temp) ((float)(temp)/(float)(1<<CELSIUS_EXTRA_BITS))
|
||||
#define TEMP_FLOAT_TO_INT(temp) ((int)((temp)*(1<<CELSIUS_EXTRA_BITS)))
|
||||
|
||||
//extern Extruder *Extruder::current;
|
||||
//extern Extruder *Extruder::current;
|
||||
#if NUM_TEMPERATURE_LOOPS > 0
|
||||
extern TemperatureController *tempController[NUM_TEMPERATURE_LOOPS];
|
||||
extern TemperatureController *tempController[NUM_TEMPERATURE_LOOPS];
|
||||
#endif
|
||||
extern uint8_t autotuneIndex;
|
||||
|
||||
|
|
2938
Repetier/HAL.cpp
2938
Repetier/HAL.cpp
File diff suppressed because it is too large
Load diff
|
@ -70,8 +70,8 @@ All known arduino boards use 64. This value is needed for the extruder timing. *
|
|||
#endif
|
||||
#include <inttypes.h>
|
||||
#include "Print.h"
|
||||
#ifdef EXTERNALSERIAL
|
||||
#define SERIAL_RX_BUFFER_SIZE 128
|
||||
#ifdef EXTERNALSERIAL
|
||||
#define SERIAL_RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
|
@ -176,16 +176,16 @@ typedef uint8_t ufast8_t;
|
|||
*/
|
||||
|
||||
#define SERIAL_BUFFER_SIZE 128
|
||||
#define SERIAL_BUFFER_MASK 127
|
||||
#undef SERIAL_TX_BUFFER_SIZE
|
||||
#undef SERIAL_TX_BUFFER_MASK
|
||||
#ifdef BIG_OUTPUT_BUFFER
|
||||
#define SERIAL_BUFFER_MASK 127
|
||||
#undef SERIAL_TX_BUFFER_SIZE
|
||||
#undef SERIAL_TX_BUFFER_MASK
|
||||
#ifdef BIG_OUTPUT_BUFFER
|
||||
#define SERIAL_TX_BUFFER_SIZE 128
|
||||
#define SERIAL_TX_BUFFER_MASK 127
|
||||
#else
|
||||
#define SERIAL_TX_BUFFER_SIZE 64
|
||||
#define SERIAL_TX_BUFFER_MASK 63
|
||||
#endif
|
||||
#endif
|
||||
|
||||
struct ring_buffer
|
||||
{
|
||||
|
@ -260,10 +260,10 @@ extern RFHardwareSerial RFSerial;
|
|||
#define OUT_LN Com::println()
|
||||
|
||||
class HAL
|
||||
{
|
||||
public:
|
||||
{
|
||||
public:
|
||||
#if FEATURE_WATCHDOG
|
||||
static bool wdPinged;
|
||||
static bool wdPinged;
|
||||
#endif
|
||||
HAL();
|
||||
virtual ~HAL();
|
||||
|
@ -713,7 +713,7 @@ public:
|
|||
WDTCSR = (1<<WDCE) | (1<<WDE); // wdt FIX for arduino mega boards
|
||||
WDTCSR = (1<<WDIE) | (1<<WDP3);
|
||||
#else
|
||||
wdt_enable(WDTO_1S);
|
||||
wdt_enable(WDTO_4S);
|
||||
#endif
|
||||
};
|
||||
inline static void stopWatchdog()
|
||||
|
@ -722,8 +722,8 @@ public:
|
|||
}
|
||||
inline static void pingWatchdog()
|
||||
{
|
||||
#if FEATURE_WATCHDOG
|
||||
wdPinged = true;
|
||||
#if FEATURE_WATCHDOG
|
||||
wdPinged = true;
|
||||
#endif
|
||||
};
|
||||
inline static float maxExtruderTimerFrequency()
|
||||
|
|
|
@ -39,9 +39,10 @@ unsigned long Printer::maxPrintAccelerationStepsPerSquareSecond[E_AXIS_ARRAY];
|
|||
unsigned long Printer::maxTravelAccelerationStepsPerSquareSecond[E_AXIS_ARRAY];
|
||||
#endif
|
||||
#if NONLINEAR_SYSTEM
|
||||
long Printer::currentDeltaPositionSteps[E_TOWER_ARRAY];
|
||||
long Printer::currentNonlinearPositionSteps[E_TOWER_ARRAY];
|
||||
uint8_t lastMoveID = 0; // Last move ID
|
||||
#else
|
||||
#endif
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
int32_t Printer::zCorrectionStepsIncluded = 0;
|
||||
#endif
|
||||
int16_t Printer::zBabystepsMissing = 0;
|
||||
|
@ -127,7 +128,7 @@ float Printer::zLength;
|
|||
float Printer::zMin;
|
||||
float Printer::feedrate; ///< Last requested feedrate.
|
||||
int Printer::feedrateMultiply; ///< Multiplier for feedrate in percent (factor 1 = 100)
|
||||
unsigned int Printer::extrudeMultiply; ///< Flow multiplier in percdent (factor 1 = 100)
|
||||
unsigned int Printer::extrudeMultiply; ///< Flow multiplier in percent (factor 1 = 100)
|
||||
float Printer::maxJerk; ///< Maximum allowed jerk in mm/s
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
float Printer::maxZJerk; ///< Maximum allowed jerk in z direction in mm/s
|
||||
|
@ -135,7 +136,7 @@ float Printer::maxZJerk; ///< Maximum allowed jerk in z direct
|
|||
float Printer::offsetX; ///< X-offset for different extruder positions.
|
||||
float Printer::offsetY; ///< Y-offset for different extruder positions.
|
||||
float Printer::offsetZ; ///< Z-offset for different extruder positions.
|
||||
speed_t Printer::vMaxReached; ///< Maximumu reached speed
|
||||
speed_t Printer::vMaxReached; ///< Maximum reached speed
|
||||
uint32_t Printer::msecondsPrinting; ///< Milliseconds of printing time (means time with heated extruder)
|
||||
float Printer::filamentPrinted; ///< mm of filament printed since counting started
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
|
@ -144,12 +145,12 @@ float Printer::backlashY;
|
|||
float Printer::backlashZ;
|
||||
uint8_t Printer::backlashDir;
|
||||
#endif
|
||||
float Printer::memoryX;
|
||||
float Printer::memoryY;
|
||||
float Printer::memoryZ;
|
||||
float Printer::memoryE;
|
||||
float Printer::memoryX = IGNORE_COORDINATE;
|
||||
float Printer::memoryY = IGNORE_COORDINATE;
|
||||
float Printer::memoryZ = IGNORE_COORDINATE;
|
||||
float Printer::memoryE = IGNORE_COORDINATE;
|
||||
float Printer::memoryF = -1;
|
||||
#if GANTRY
|
||||
#if GANTRY && !defined(FAST_COREXYZ)
|
||||
int8_t Printer::motorX;
|
||||
int8_t Printer::motorYorZ;
|
||||
#endif
|
||||
|
@ -212,8 +213,13 @@ void Endstops::update() {
|
|||
newRead |= ENDSTOP_Z2_MINMAX_ID;
|
||||
#endif
|
||||
#if FEATURE_Z_PROBE
|
||||
#if Z_PROBE_PIN == Z_MIN_PIN && MIN_HARDWARE_ENDSTOP_Z
|
||||
if(newRead & ENDSTOP_Z_MIN_ID) // prevent different results causing confusion
|
||||
newRead |= ENDSTOP_Z_PROBE_ID;
|
||||
#else
|
||||
if(Z_PROBE_ON_HIGH ? READ(Z_PROBE_PIN) : !READ(Z_PROBE_PIN))
|
||||
newRead |= ENDSTOP_Z_PROBE_ID;
|
||||
#endif
|
||||
#endif
|
||||
lastRead &= newRead;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
|
@ -230,9 +236,7 @@ void Endstops::update() {
|
|||
lastState2 = lastRead2;
|
||||
accumulator2 |= lastState2;
|
||||
#endif
|
||||
#ifdef DEBUG_ENDSTOPS
|
||||
report();
|
||||
#endif
|
||||
if (Printer::debugEndStop()) Endstops::report();
|
||||
} else {
|
||||
lastState = lastRead;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
|
@ -287,32 +291,39 @@ void Printer::constrainDestinationCoords()
|
|||
{
|
||||
if(isNoDestinationCheck()) return;
|
||||
#if min_software_endstop_x
|
||||
if (destinationSteps[X_AXIS] < xMinSteps) Printer::destinationSteps[X_AXIS] = Printer::xMinSteps;
|
||||
if (Printer::destinationSteps[X_AXIS] < xMinSteps) Printer::destinationSteps[X_AXIS] = Printer::xMinSteps;
|
||||
#endif
|
||||
#if min_software_endstop_y
|
||||
if (destinationSteps[Y_AXIS] < yMinSteps) Printer::destinationSteps[Y_AXIS] = Printer::yMinSteps;
|
||||
if (Printer::destinationSteps[Y_AXIS] < yMinSteps) Printer::destinationSteps[Y_AXIS] = Printer::yMinSteps;
|
||||
#endif
|
||||
#if min_software_endstop_z
|
||||
if (isAutolevelActive() == false && destinationSteps[Z_AXIS] < zMinSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMinSteps;
|
||||
if (isAutolevelActive() == false && Printer::destinationSteps[Z_AXIS] < zMinSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMinSteps;
|
||||
#endif
|
||||
|
||||
#if max_software_endstop_x
|
||||
if (destinationSteps[X_AXIS] > Printer::xMaxSteps) Printer::destinationSteps[X_AXIS] = Printer::xMaxSteps;
|
||||
if (Printer::destinationSteps[X_AXIS] > Printer::xMaxSteps) Printer::destinationSteps[X_AXIS] = Printer::xMaxSteps;
|
||||
#endif
|
||||
#if max_software_endstop_y
|
||||
if (destinationSteps[Y_AXIS] > Printer::yMaxSteps) Printer::destinationSteps[Y_AXIS] = Printer::yMaxSteps;
|
||||
if (Printer::destinationSteps[Y_AXIS] > Printer::yMaxSteps) Printer::destinationSteps[Y_AXIS] = Printer::yMaxSteps;
|
||||
#endif
|
||||
#if max_software_endstop_z
|
||||
if (isAutolevelActive() == false && destinationSteps[Z_AXIS] > Printer::zMaxSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMaxSteps;
|
||||
if (isAutolevelActive() == false && Printer::destinationSteps[Z_AXIS] > Printer::zMaxSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMaxSteps;
|
||||
#endif
|
||||
EVENT_CONTRAIN_DESTINATION_COORDINATES
|
||||
}
|
||||
#endif
|
||||
void Printer::setDebugLevel(uint8_t newLevel) {
|
||||
debugLevel = newLevel;
|
||||
if(newLevel != debugLevel) {
|
||||
debugLevel = newLevel;
|
||||
if(debugDryrun()) {
|
||||
// Disable all heaters in case they were on
|
||||
Extruder::disableAllHeater();
|
||||
}
|
||||
}
|
||||
Com::printFLN(PSTR("DebugLevel:"),(int)newLevel);
|
||||
}
|
||||
void Printer::toggleEcho() {
|
||||
setDebugLevel(debugLevel ^ 32);
|
||||
setDebugLevel(debugLevel ^ 1);
|
||||
}
|
||||
void Printer::toggleInfo() {
|
||||
setDebugLevel(debugLevel ^ 2);
|
||||
|
@ -329,10 +340,13 @@ void Printer::toggleCommunication() {
|
|||
void Printer::toggleNoMoves() {
|
||||
setDebugLevel(debugLevel ^ 32);
|
||||
}
|
||||
void Printer::toggleEndStop() {
|
||||
setDebugLevel(debugLevel ^ 64);
|
||||
}
|
||||
|
||||
bool Printer::isPositionAllowed(float x,float y,float z)
|
||||
{
|
||||
if(isNoDestinationCheck()) return true;
|
||||
if(isNoDestinationCheck()) return true;
|
||||
bool allowed = true;
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
allowed &= (z >= 0) && (z <= zLength + 0.05 + ENDSTOP_Z_BACK_ON_HOME);
|
||||
|
@ -390,9 +404,13 @@ void Printer::reportPrinterMode() {
|
|||
}
|
||||
void Printer::updateDerivedParameter()
|
||||
{
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
#if NONLINEAR_SYSTEM
|
||||
travelMovesPerSecond = EEPROM::deltaSegmentsPerSecondMove();
|
||||
printMovesPerSecond = EEPROM::deltaSegmentsPerSecondPrint();
|
||||
if(travelMovesPerSecond < 15) travelMovesPerSecond = 15; // lower values make no sense and can cause serious problems
|
||||
if(printMovesPerSecond < 15) printMovesPerSecond = 15;
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
axisStepsPerMM[X_AXIS] = axisStepsPerMM[Y_AXIS] = axisStepsPerMM[Z_AXIS];
|
||||
maxAccelerationMMPerSquareSecond[X_AXIS] = maxAccelerationMMPerSquareSecond[Y_AXIS] = maxAccelerationMMPerSquareSecond[Z_AXIS];
|
||||
homingFeedrate[X_AXIS] = homingFeedrate[Y_AXIS] = homingFeedrate[Z_AXIS];
|
||||
|
@ -489,6 +507,8 @@ void Printer::updateDerivedParameter()
|
|||
minimumSpeed = accel * sqrt(2.0f / (axisStepsPerMM[X_AXIS]*accel));
|
||||
accel = RMath::max(maxAccelerationMMPerSquareSecond[Z_AXIS], maxTravelAccelerationMMPerSquareSecond[Z_AXIS]);
|
||||
minimumZSpeed = accel * sqrt(2.0f / (axisStepsPerMM[Z_AXIS] * accel));
|
||||
//Com::printFLN(PSTR("Minimum Speed:"),minimumSpeed);
|
||||
//Com::printFLN(PSTR("Minimum Speed Z:"),minimumZSpeed);
|
||||
#if DISTORTION_CORRECTION
|
||||
distortion.updateDerived();
|
||||
#endif // DISTORTION_CORRECTION
|
||||
|
@ -518,7 +538,7 @@ void Printer::kill(uint8_t only_steppers)
|
|||
Extruder::disableAllExtruderMotors();
|
||||
if(!only_steppers)
|
||||
{
|
||||
for(uint8_t i = 0; i < NUM_TEMPERATURE_LOOPS; i++)
|
||||
for(uint8_t i = 0; i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(0, i);
|
||||
Extruder::setHeatedBedTemperature(0);
|
||||
UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_STANDBY_ID));
|
||||
|
@ -537,6 +557,7 @@ void Printer::kill(uint8_t only_steppers)
|
|||
#endif
|
||||
pwm_pos[PWM_BOARD_FAN] = 0;
|
||||
#endif // FAN_BOARD_PIN
|
||||
Commands::printTemperatures(false);
|
||||
}
|
||||
|
||||
void Printer::updateAdvanceFlags()
|
||||
|
@ -571,7 +592,7 @@ uint8_t Printer::moveTo(float x,float y,float z,float e,float f)
|
|||
feedrate = f;
|
||||
#if NONLINEAR_SYSTEM
|
||||
// Disable software endstop or we get wrong distances when length < real length
|
||||
if (!PrintLine::queueDeltaMove(ALWAYS_CHECK_ENDSTOPS, true, false))
|
||||
if (!PrintLine::queueNonlinearMove(ALWAYS_CHECK_ENDSTOPS, true, false))
|
||||
{
|
||||
Com::printWarningFLN(PSTR("moveTo / queueDeltaMove returns error"));
|
||||
return 0;
|
||||
|
@ -598,16 +619,7 @@ uint8_t Printer::moveToReal(float x, float y, float z, float e, float f,bool pat
|
|||
z = currentPosition[Z_AXIS];
|
||||
else
|
||||
currentPosition[Z_AXIS] = z;
|
||||
#if FEATURE_AUTOLEVEL
|
||||
if(isAutolevelActive())
|
||||
transformToPrinter(x + Printer::offsetX, y + Printer::offsetY, z + Printer::offsetZ, x, y, z);
|
||||
else
|
||||
#endif // FEATURE_AUTOLEVEL
|
||||
{
|
||||
x += Printer::offsetX;
|
||||
y += Printer::offsetY;
|
||||
z += Printer::offsetZ;
|
||||
}
|
||||
transformToPrinter(x + Printer::offsetX, y + Printer::offsetY, z + Printer::offsetZ, x, y, z);
|
||||
// There was conflicting use of IGNOR_COORDINATE
|
||||
destinationSteps[X_AXIS] = static_cast<int32_t>(floor(x * axisStepsPerMM[X_AXIS] + 0.5f));
|
||||
destinationSteps[Y_AXIS] = static_cast<int32_t>(floor(y * axisStepsPerMM[Y_AXIS] + 0.5f));
|
||||
|
@ -622,7 +634,7 @@ uint8_t Printer::moveToReal(float x, float y, float z, float e, float f,bool pat
|
|||
feedrate = f;
|
||||
|
||||
#if NONLINEAR_SYSTEM
|
||||
if (!PrintLine::queueDeltaMove(ALWAYS_CHECK_ENDSTOPS, pathOptimize, true))
|
||||
if (!PrintLine::queueNonlinearMove(ALWAYS_CHECK_ENDSTOPS, pathOptimize, true))
|
||||
{
|
||||
Com::printWarningFLN(PSTR("moveToReal / queueDeltaMove returns error"));
|
||||
SHOWM(x);
|
||||
|
@ -653,11 +665,8 @@ void Printer::updateCurrentPosition(bool copyLastCmd)
|
|||
#else
|
||||
currentPosition[Z_AXIS] = static_cast<float>(currentPositionSteps[Z_AXIS] - zCorrectionStepsIncluded) * invAxisStepsPerMM[Z_AXIS];
|
||||
#endif
|
||||
#if FEATURE_AUTOLEVEL
|
||||
if(isAutolevelActive())
|
||||
transformFromPrinter(currentPosition[X_AXIS], currentPosition[Y_AXIS], currentPosition[Z_AXIS],
|
||||
currentPosition[X_AXIS], currentPosition[Y_AXIS], currentPosition[Z_AXIS]);
|
||||
#endif // FEATURE_AUTOLEVEL
|
||||
transformFromPrinter(currentPosition[X_AXIS], currentPosition[Y_AXIS], currentPosition[Z_AXIS],
|
||||
currentPosition[X_AXIS], currentPosition[Y_AXIS], currentPosition[Z_AXIS]);
|
||||
currentPosition[X_AXIS] -= Printer::offsetX;
|
||||
currentPosition[Y_AXIS] -= Printer::offsetY;
|
||||
currentPosition[Z_AXIS] -= Printer::offsetZ;
|
||||
|
@ -674,7 +683,7 @@ void Printer::updateCurrentPosition(bool copyLastCmd)
|
|||
|
||||
For the computation of the destination, the following facts are considered:
|
||||
- Are units inches or mm.
|
||||
- Reltive or absolute positioning with special case only extruder relative.
|
||||
- Relative or absolute positioning with special case only extruder relative.
|
||||
- Offset in x and y direction for multiple extruder support.
|
||||
*/
|
||||
|
||||
|
@ -683,7 +692,7 @@ uint8_t Printer::setDestinationStepsFromGCode(GCode *com)
|
|||
register int32_t p;
|
||||
float x, y, z;
|
||||
#if FEATURE_RETRACTION
|
||||
if(com->hasNoXYZ() && com->hasE() && isAutoretract()) { // convert into autoretract
|
||||
if(com->hasNoXYZ() && com->hasE() && isAutoretract()) { // convert into auto retract
|
||||
if(relativeCoordinateMode || relativeExtruderCoordinateMode) {
|
||||
Extruder::current->retract(com->E < 0,false);
|
||||
} else {
|
||||
|
@ -705,18 +714,7 @@ uint8_t Printer::setDestinationStepsFromGCode(GCode *com)
|
|||
if(com->hasY()) currentPosition[Y_AXIS] = (lastCmdPos[Y_AXIS] += convertToMM(com->Y));
|
||||
if(com->hasZ()) currentPosition[Z_AXIS] = (lastCmdPos[Z_AXIS] += convertToMM(com->Z));
|
||||
}
|
||||
#if FEATURE_AUTOLEVEL
|
||||
if(isAutolevelActive())
|
||||
{
|
||||
transformToPrinter(lastCmdPos[X_AXIS] + Printer::offsetX, lastCmdPos[Y_AXIS] + Printer::offsetY, lastCmdPos[Z_AXIS] + Printer::offsetZ, x, y, z);
|
||||
}
|
||||
else
|
||||
#endif // FEATURE_AUTOLEVEL
|
||||
{
|
||||
x = lastCmdPos[X_AXIS] + Printer::offsetX;
|
||||
y = lastCmdPos[Y_AXIS] + Printer::offsetY;
|
||||
z = lastCmdPos[Z_AXIS] + Printer::offsetZ;
|
||||
}
|
||||
transformToPrinter(lastCmdPos[X_AXIS] + Printer::offsetX, lastCmdPos[Y_AXIS] + Printer::offsetY, lastCmdPos[Z_AXIS] + Printer::offsetZ, x, y, z);
|
||||
destinationSteps[X_AXIS] = static_cast<int32_t>(floor(x * axisStepsPerMM[X_AXIS] + 0.5f));
|
||||
destinationSteps[Y_AXIS] = static_cast<int32_t>(floor(y * axisStepsPerMM[Y_AXIS] + 0.5f));
|
||||
destinationSteps[Z_AXIS] = static_cast<int32_t>(floor(z * axisStepsPerMM[Z_AXIS] + 0.5f));
|
||||
|
@ -831,7 +829,7 @@ void Printer::setup()
|
|||
SET_OUTPUT(X_STEP_PIN);
|
||||
SET_OUTPUT(Y_STEP_PIN);
|
||||
SET_OUTPUT(Z_STEP_PIN);
|
||||
|
||||
endXYZSteps();
|
||||
//Initialize Dir Pins
|
||||
#if X_DIR_PIN > -1
|
||||
SET_OUTPUT(X_DIR_PIN);
|
||||
|
@ -856,7 +854,7 @@ void Printer::setup()
|
|||
SET_OUTPUT(Z_ENABLE_PIN);
|
||||
WRITE(Z_ENABLE_PIN, !Z_ENABLE_ON);
|
||||
#endif
|
||||
#if FEATURE_TWO_XSTEPPER
|
||||
#if FEATURE_TWO_XSTEPPER || DUAL_X_AXIS
|
||||
SET_OUTPUT(X2_STEP_PIN);
|
||||
SET_OUTPUT(X2_DIR_PIN);
|
||||
#if X2_ENABLE_PIN > -1
|
||||
|
@ -1063,7 +1061,7 @@ void Printer::setup()
|
|||
CNCDriver::initialize();
|
||||
#endif // defined
|
||||
|
||||
#if GANTRY
|
||||
#if GANTRY && !defined(FAST_COREXYZ)
|
||||
Printer::motorX = 0;
|
||||
Printer::motorYorZ = 0;
|
||||
#endif
|
||||
|
@ -1110,7 +1108,7 @@ void Printer::setup()
|
|||
xMin = X_MIN_POS;
|
||||
yMin = Y_MIN_POS;
|
||||
zMin = Z_MIN_POS;
|
||||
#if NONLINEAR_SYSTEM
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
radius0 = ROD_RADIUS;
|
||||
#endif
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
|
@ -1147,7 +1145,7 @@ void Printer::setup()
|
|||
HAL::setupTimer();
|
||||
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentDeltaPositionSteps);
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentNonlinearPositionSteps);
|
||||
|
||||
#if DELTA_HOME_ON_POWER
|
||||
homeAxis(true,true,true);
|
||||
|
@ -1242,7 +1240,7 @@ void Printer::deltaMoveToTopEndstops(float feedrate)
|
|||
Printer::stepsRemainingAtYHit = -1;
|
||||
Printer::stepsRemainingAtZHit = -1;
|
||||
setHoming(true);
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentDeltaPositionSteps);
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, (zMaxSteps + EEPROM::deltaDiagonalRodLength()*axisStepsPerMM[Z_AXIS]) * 1.5, 0, feedrate, true, true);
|
||||
offsetX = offsetY = offsetZ = 0;
|
||||
setHoming(false);
|
||||
|
@ -1250,7 +1248,7 @@ void Printer::deltaMoveToTopEndstops(float feedrate)
|
|||
void Printer::homeXAxis()
|
||||
{
|
||||
destinationSteps[X_AXIS] = 0;
|
||||
if (!PrintLine::queueDeltaMove(true,false,false))
|
||||
if (!PrintLine::queueNonlinearMove(true,false,false))
|
||||
{
|
||||
Com::printWarningFLN(PSTR("homeXAxis / queueDeltaMove returns error"));
|
||||
}
|
||||
|
@ -1258,7 +1256,7 @@ void Printer::homeXAxis()
|
|||
void Printer::homeYAxis()
|
||||
{
|
||||
Printer::destinationSteps[Y_AXIS] = 0;
|
||||
if (!PrintLine::queueDeltaMove(true,false,false))
|
||||
if (!PrintLine::queueNonlinearMove(true,false,false))
|
||||
{
|
||||
Com::printWarningFLN(PSTR("homeYAxis / queueDeltaMove returns error"));
|
||||
}
|
||||
|
@ -1270,13 +1268,13 @@ void Printer::homeZAxis() // Delta z homing
|
|||
deltaMoveToTopEndstops(Printer::homingFeedrate[Z_AXIS]);
|
||||
// New safe homing routine by Kyrre Aalerud
|
||||
// This method will safeguard against sticky endstops such as may be gotten cheaply from china.
|
||||
// This can lead to headcrashes and even fire, thus a safer algorithm to ensure the endstops actually respond as expected.
|
||||
// This can lead to head crashes and even fire, thus a safer algorithm to ensure the endstops actually respond as expected.
|
||||
//Endstops::report();
|
||||
// Check that all endstops (XYZ) were hit
|
||||
Endstops::fillFromAccumulator();
|
||||
if (Endstops::xMax() && Endstops::yMax() && Endstops::zMax()) {
|
||||
// Back off for retest
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE, 0, Printer::homingFeedrate[Z_AXIS]/ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, true);
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE, 0, Printer::homingFeedrate[Z_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, true);
|
||||
//Endstops::report();
|
||||
// Check for proper release of all (XYZ) endstops
|
||||
if (!(Endstops::xMax() || Endstops::yMax() || Endstops::zMax())) {
|
||||
|
@ -1323,10 +1321,10 @@ void Printer::homeZAxis() // Delta z homing
|
|||
currentPositionSteps[X_AXIS] = 0; // here we should be
|
||||
currentPositionSteps[Y_AXIS] = 0;
|
||||
currentPositionSteps[Z_AXIS] = zMaxSteps;
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps,currentDeltaPositionSteps);
|
||||
currentDeltaPositionSteps[A_TOWER] -= dx;
|
||||
currentDeltaPositionSteps[B_TOWER] -= dy;
|
||||
currentDeltaPositionSteps[C_TOWER] -= dz;
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps,currentNonlinearPositionSteps);
|
||||
currentNonlinearPositionSteps[A_TOWER] -= dx;
|
||||
currentNonlinearPositionSteps[B_TOWER] -= dy;
|
||||
currentNonlinearPositionSteps[C_TOWER] -= dz;
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, dm, 0, homingFeedrate[Z_AXIS], true, false);
|
||||
currentPositionSteps[X_AXIS] = 0; // now we are really here
|
||||
currentPositionSteps[Y_AXIS] = 0;
|
||||
|
@ -1334,10 +1332,10 @@ void Printer::homeZAxis() // Delta z homing
|
|||
coordinateOffset[X_AXIS] = 0;
|
||||
coordinateOffset[Y_AXIS] = 0;
|
||||
coordinateOffset[Z_AXIS] = 0;
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentDeltaPositionSteps);
|
||||
realDeltaPositionSteps[A_TOWER] = currentDeltaPositionSteps[A_TOWER];
|
||||
realDeltaPositionSteps[B_TOWER] = currentDeltaPositionSteps[B_TOWER];
|
||||
realDeltaPositionSteps[C_TOWER] = currentDeltaPositionSteps[C_TOWER];
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
realDeltaPositionSteps[A_TOWER] = currentNonlinearPositionSteps[A_TOWER];
|
||||
realDeltaPositionSteps[B_TOWER] = currentNonlinearPositionSteps[B_TOWER];
|
||||
realDeltaPositionSteps[C_TOWER] = currentNonlinearPositionSteps[C_TOWER];
|
||||
//maxDeltaPositionSteps = currentDeltaPositionSteps[X_AXIS];
|
||||
#if defined(ENDSTOP_Z_BACK_ON_HOME)
|
||||
if(ENDSTOP_Z_BACK_ON_HOME > 0)
|
||||
|
@ -1354,7 +1352,7 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // Delta homing code
|
|||
if (!(X_MAX_PIN > -1 && Y_MAX_PIN > -1 && Z_MAX_PIN > -1
|
||||
&& MAX_HARDWARE_ENDSTOP_X && MAX_HARDWARE_ENDSTOP_Y && MAX_HARDWARE_ENDSTOP_Z))
|
||||
{
|
||||
Com::printErrorFLN(PSTR("Hardware setup inconsistent. Delta cannot home wihtout max endstops."));
|
||||
Com::printErrorFLN(PSTR("Hardware setup inconsistent. Delta cannot home without max endstops."));
|
||||
}
|
||||
// The delta has to have home capability to zero and set position,
|
||||
// so the redundant check is only an opportunity to
|
||||
|
@ -1396,7 +1394,7 @@ void Printer::homeXAxis()
|
|||
currentPositionSteps[X_AXIS] = -steps;
|
||||
currentPositionSteps[Y_AXIS] = 0;
|
||||
setHoming(true);
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentDeltaPositionSteps);
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
PrintLine::moveRelativeDistanceInSteps(2*steps,0,0,0,homingFeedrate[X_AXIS],true,true);
|
||||
currentPositionSteps[X_AXIS] = (X_HOME_DIR == -1) ? xMinSteps-offX : xMaxSteps+offX;
|
||||
currentPositionSteps[Y_AXIS] = 0; //(Y_HOME_DIR == -1) ? yMinSteps-offY : yMaxSteps+offY;
|
||||
|
@ -1414,7 +1412,7 @@ void Printer::homeXAxis()
|
|||
currentPositionSteps[Y_AXIS] = 0; //(Y_HOME_DIR == -1) ? yMinSteps-offY : yMaxSteps+offY;
|
||||
coordinateOffset[X_AXIS] = 0;
|
||||
coordinateOffset[Y_AXIS] = 0;
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentDeltaPositionSteps);
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#if NUM_EXTRUDER>1
|
||||
PrintLine::moveRelativeDistanceInSteps((Extruder::current->xOffset-offX) * X_HOME_DIR,(Extruder::current->yOffset-offY) * Y_HOME_DIR,0,0,homingFeedrate[X_AXIS],true,false);
|
||||
#endif
|
||||
|
@ -1424,12 +1422,48 @@ void Printer::homeYAxis()
|
|||
{
|
||||
// Dummy function x and y homing must occur together
|
||||
}
|
||||
#else // cartesian printer
|
||||
#else // Cartesian printer
|
||||
void Printer::homeXAxis()
|
||||
{
|
||||
{
|
||||
long steps;
|
||||
UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_X_ID));
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
setHoming(true);
|
||||
#if DUAL_X_AXIS && NUM_EXTRUDER == 2
|
||||
Extruder *curExtruder = Extruder::current;
|
||||
Extruder::current = &extruder[0];
|
||||
steps = (Printer::xMaxSteps - Printer::xMinSteps);
|
||||
currentPositionSteps[X_AXIS] = steps;
|
||||
PrintLine::moveRelativeDistanceInSteps(-2 * steps, 0, 0, 0, homingFeedrate[X_AXIS], true, true);
|
||||
setHoming(false);
|
||||
PrintLine::moveRelativeDistanceInSteps(axisStepsPerMM[X_AXIS] * ENDSTOP_X_BACK_MOVE,0,0,0,homingFeedrate[X_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, false);
|
||||
setHoming(true);
|
||||
PrintLine::moveRelativeDistanceInSteps(-axisStepsPerMM[X_AXIS] * 2 * ENDSTOP_X_BACK_MOVE,0,0,0,homingFeedrate[X_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, true);
|
||||
setHoming(false);
|
||||
#if defined(ENDSTOP_X_BACK_ON_HOME)
|
||||
if(ENDSTOP_X_BACK_ON_HOME > 0)
|
||||
PrintLine::moveRelativeDistanceInSteps(axisStepsPerMM[X_AXIS] * ENDSTOP_X_BACK_ON_HOME,0,0,0,homingFeedrate[X_AXIS], true, false);
|
||||
#endif
|
||||
Extruder::current = &extruder[1];
|
||||
currentPositionSteps[X_AXIS] = -steps;
|
||||
PrintLine::moveRelativeDistanceInSteps(2 * steps, 0, 0, 0, homingFeedrate[X_AXIS], true, true);
|
||||
setHoming(false);
|
||||
PrintLine::moveRelativeDistanceInSteps(-axisStepsPerMM[X_AXIS] * ENDSTOP_X_BACK_MOVE,0,0,0,homingFeedrate[X_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, false);
|
||||
setHoming(true);
|
||||
PrintLine::moveRelativeDistanceInSteps(axisStepsPerMM[X_AXIS] * 2 * ENDSTOP_X_BACK_MOVE,0,0,0,homingFeedrate[X_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, true);
|
||||
setHoming(false);
|
||||
#if defined(ENDSTOP_X_BACK_ON_HOME)
|
||||
if(ENDSTOP_X_BACK_ON_HOME > 0)
|
||||
PrintLine::moveRelativeDistanceInSteps(-axisStepsPerMM[X_AXIS] * ENDSTOP_X_BACK_ON_HOME,0,0,0,homingFeedrate[X_AXIS], true, false);
|
||||
#endif
|
||||
Extruder::current = curExtruder;
|
||||
// Now position current extrude on x = 0
|
||||
PrintLine::moveRelativeDistanceInSteps(-Extruder::current->xOffset, 0, 0, 0, homingFeedrate[X_AXIS], true, true);
|
||||
currentPositionSteps[X_AXIS] = xMinSteps;
|
||||
#else
|
||||
if ((MIN_HARDWARE_ENDSTOP_X && X_MIN_PIN > -1 && X_HOME_DIR == -1) || (MAX_HARDWARE_ENDSTOP_X && X_MAX_PIN > -1 && X_HOME_DIR == 1))
|
||||
{
|
||||
coordinateOffset[X_AXIS] = 0;
|
||||
long offX = 0;
|
||||
#if NUM_EXTRUDER > 1
|
||||
for(uint8_t i = 0; i < NUM_EXTRUDER; i++)
|
||||
|
@ -1438,14 +1472,18 @@ void Printer::homeXAxis()
|
|||
#else
|
||||
offX = RMath::min(offX,extruder[i].xOffset);
|
||||
#endif
|
||||
// Reposition extruder that way, that all extruders can be selected at home pos.
|
||||
// Reposition extruder that way, that all extruders can be selected at home position.
|
||||
#endif // NUM_EXTRUDER > 1
|
||||
UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_X_ID));
|
||||
steps = (Printer::xMaxSteps - Printer::xMinSteps) * X_HOME_DIR;
|
||||
currentPositionSteps[X_AXIS] = -steps;
|
||||
setHoming(true);
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(2 * steps, 0, 0, 0, homingFeedrate[X_AXIS], true, true);
|
||||
currentPositionSteps[X_AXIS] = (X_HOME_DIR == -1) ? xMinSteps - offX : xMaxSteps + offX;
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(axisStepsPerMM[X_AXIS] * -ENDSTOP_X_BACK_MOVE * X_HOME_DIR,0,0,0,homingFeedrate[X_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, false);
|
||||
PrintLine::moveRelativeDistanceInSteps(axisStepsPerMM[X_AXIS] * 2 * ENDSTOP_X_BACK_MOVE * X_HOME_DIR,0,0,0,homingFeedrate[X_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, true);
|
||||
setHoming(false);
|
||||
|
@ -1454,6 +1492,9 @@ void Printer::homeXAxis()
|
|||
PrintLine::moveRelativeDistanceInSteps(axisStepsPerMM[X_AXIS] * -ENDSTOP_X_BACK_ON_HOME * X_HOME_DIR,0,0,0,homingFeedrate[X_AXIS], true, true);
|
||||
#endif
|
||||
currentPositionSteps[X_AXIS] = (X_HOME_DIR == -1) ? xMinSteps - offX : xMaxSteps + offX;
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
#if NUM_EXTRUDER > 1
|
||||
#if X_HOME_DIR < 0
|
||||
PrintLine::moveRelativeDistanceInSteps((Extruder::current->xOffset - offX) * X_HOME_DIR,0,0,0,homingFeedrate[X_AXIS], true, true);
|
||||
|
@ -1462,6 +1503,7 @@ void Printer::homeXAxis()
|
|||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void Printer::homeYAxis()
|
||||
|
@ -1469,6 +1511,7 @@ void Printer::homeYAxis()
|
|||
long steps;
|
||||
if ((MIN_HARDWARE_ENDSTOP_Y && Y_MIN_PIN > -1 && Y_HOME_DIR == -1) || (MAX_HARDWARE_ENDSTOP_Y && Y_MAX_PIN > -1 && Y_HOME_DIR == 1))
|
||||
{
|
||||
coordinateOffset[Y_AXIS] = 0;
|
||||
long offY = 0;
|
||||
#if NUM_EXTRUDER > 1
|
||||
for(uint8_t i = 0; i < NUM_EXTRUDER; i++)
|
||||
|
@ -1483,8 +1526,14 @@ void Printer::homeYAxis()
|
|||
steps = (yMaxSteps-Printer::yMinSteps) * Y_HOME_DIR;
|
||||
currentPositionSteps[Y_AXIS] = -steps;
|
||||
setHoming(true);
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(0,2 * steps,0,0,homingFeedrate[Y_AXIS],true,true);
|
||||
currentPositionSteps[Y_AXIS] = (Y_HOME_DIR == -1) ? yMinSteps-offY : yMaxSteps+offY;
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS] * -ENDSTOP_Y_BACK_MOVE * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR,true,false);
|
||||
PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS] * 2 * ENDSTOP_Y_BACK_MOVE * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR,true,true);
|
||||
setHoming(false);
|
||||
|
@ -1493,6 +1542,9 @@ void Printer::homeYAxis()
|
|||
PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS] * -ENDSTOP_Y_BACK_ON_HOME * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false);
|
||||
#endif
|
||||
currentPositionSteps[Y_AXIS] = (Y_HOME_DIR == -1) ? yMinSteps - offY : yMaxSteps + offY;
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
#if NUM_EXTRUDER > 1
|
||||
#if Y_HOME_DIR < 0
|
||||
PrintLine::moveRelativeDistanceInSteps(0,(Extruder::current->yOffset - offY) * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false);
|
||||
|
@ -1504,17 +1556,24 @@ void Printer::homeYAxis()
|
|||
}
|
||||
#endif
|
||||
|
||||
void Printer::homeZAxis() // cartesian homing
|
||||
void Printer::homeZAxis() // Cartesian homing
|
||||
{
|
||||
long steps;
|
||||
if ((MIN_HARDWARE_ENDSTOP_Z && Z_MIN_PIN > -1 && Z_HOME_DIR == -1) || (MAX_HARDWARE_ENDSTOP_Z && Z_MAX_PIN > -1 && Z_HOME_DIR == 1))
|
||||
{
|
||||
coordinateOffset[Z_AXIS] = 0;
|
||||
UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_Z_ID));
|
||||
steps = (zMaxSteps - zMinSteps) * Z_HOME_DIR;
|
||||
currentPositionSteps[Z_AXIS] = -steps;
|
||||
setHoming(true);
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(0,0,2 * steps,0,homingFeedrate[Z_AXIS],true,true);
|
||||
currentPositionSteps[Z_AXIS] = (Z_HOME_DIR == -1) ? zMinSteps : zMaxSteps;
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE * Z_HOME_DIR,0,homingFeedrate[Z_AXIS] / ENDSTOP_Z_RETEST_REDUCTION_FACTOR,true,false);
|
||||
#if defined(ZHOME_WAIT_UNSWING) && ZHOME_WAIT_UNSWING > 0
|
||||
HAL::delayMilliseconds(ZHOME_WAIT_UNSWING);
|
||||
|
@ -1522,26 +1581,28 @@ void Printer::homeZAxis() // cartesian homing
|
|||
PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS] * 2 * ENDSTOP_Z_BACK_MOVE * Z_HOME_DIR,0,homingFeedrate[Z_AXIS] / ENDSTOP_Z_RETEST_REDUCTION_FACTOR,true,true);
|
||||
setHoming(false);
|
||||
int32_t zCorrection = 0;
|
||||
#if MIN_HARDWARE_ENDSTOP_Z && FEATURE_Z_PROBE && Z_PROBE_PIN==Z_MIN_PIN
|
||||
#if Z_HOME_DIR < 0 && MIN_HARDWARE_ENDSTOP_Z && FEATURE_Z_PROBE && Z_PROBE_PIN == Z_MIN_PIN
|
||||
// Fix error from z probe testing
|
||||
zCorrection -= axisStepsPerMM[Z_AXIS]*EEPROM::zProbeHeight();
|
||||
#endif
|
||||
#if defined(ENDSTOP_Z_BACK_ON_HOME)
|
||||
// If we want to go up a bit more for some reason
|
||||
if(ENDSTOP_Z_BACK_ON_HOME > 0)
|
||||
zCorrection -= axisStepsPerMM[Z_AXIS]*ENDSTOP_Z_BACK_ON_HOME * Z_HOME_DIR;
|
||||
zCorrection -= axisStepsPerMM[Z_AXIS] * ENDSTOP_Z_BACK_ON_HOME * Z_HOME_DIR;
|
||||
#endif
|
||||
#if Z_HOME_DIR < 0
|
||||
// Fix bed coating
|
||||
zCorrection += axisStepsPerMM[Z_AXIS] * Printer::zBedOffset;
|
||||
#else
|
||||
currentPositionSteps[Z_AXIS] -= zBedOffset * axisStepsPerMM[Z_AXIS]; // Correct bed coating
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(0,0,zCorrection,0,homingFeedrate[Z_AXIS],true,false);
|
||||
currentPositionSteps[Z_AXIS] = ((Z_HOME_DIR == -1) ? zMinSteps : zMaxSteps - Printer::zBedOffset * axisStepsPerMM[Z_AXIS]);
|
||||
#if NUM_EXTRUDER > 0
|
||||
currentPositionSteps[Z_AXIS] -= Extruder::current->zOffset;
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == TUGA
|
||||
currentDeltaPositionSteps[C_TOWER] = currentPositionSteps[Z_AXIS];
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@ -1578,25 +1639,27 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print
|
|||
if(zaxis) homeZAxis();
|
||||
if(yaxis) homeYAxis();
|
||||
if(xaxis) homeXAxis();
|
||||
#elif HOMING_ORDER == HOME_ORDER_ZXYTZ
|
||||
#elif HOMING_ORDER == HOME_ORDER_ZXYTZ || HOMING_ORDER == HOME_ORDER_XYTZ
|
||||
{
|
||||
float actTemp[NUM_EXTRUDER];
|
||||
for(int i = 0;i < NUM_EXTRUDER; i++)
|
||||
actTemp[i] = extruder[i].tempControl.targetTemperatureC;
|
||||
if(zaxis) {
|
||||
#if HOMING_ORDER == HOME_ORDER_ZXYTZ
|
||||
homeZAxis();
|
||||
Printer::moveToReal(IGNORE_COORDINATE,IGNORE_COORDINATE,ZHOME_HEAT_HEIGHT,IGNORE_COORDINATE,homingFeedrate[Z_AXIS]);
|
||||
#endif
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
#if ZHOME_HEAT_ALL
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i],static_cast<float>(ZHOME_MIN_TEMPERATURE)),i,false,false);
|
||||
}
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
if(actTemp[i] < ZHOME_MIN_TEMPERATURE)
|
||||
if(extruder[i].tempControl.currentTemperatureC < ZHOME_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i],static_cast<float>(ZHOME_MIN_TEMPERATURE)),i,false,true);
|
||||
}
|
||||
#else
|
||||
if(actTemp[Extruder::current->id] < ZHOME_MIN_TEMPERATURE)
|
||||
if(extruder[Extruder::current->id].tempControl.currentTemperatureC < ZHOME_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[Extruder::current->id],static_cast<float>(ZHOME_MIN_TEMPERATURE)),Extruder::current->id,false,true);
|
||||
#endif
|
||||
}
|
||||
|
@ -1641,16 +1704,17 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print
|
|||
currentPositionSteps[Z_AXIS] += Printer::zCorrectionStepsIncluded;
|
||||
}
|
||||
#endif
|
||||
if(Z_HOME_DIR < 0) startZ = Printer::zMin;
|
||||
else startZ = Printer::zMin + Printer::zLength - zBedOffset;
|
||||
moveToReal(IGNORE_COORDINATE, IGNORE_COORDINATE, ZHOME_HEAT_HEIGHT, IGNORE_COORDINATE, homingFeedrate[X_AXIS]);
|
||||
#if ZHOME_HEAT_ALL
|
||||
for(int i = 0;i < NUM_EXTRUDER; i++)
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(actTemp[i],i,false,false);
|
||||
for(int i = 0;i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(actTemp[i],i,false,true);
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(actTemp[i],i,false, actTemp[i] > MAX_ROOM_TEMPERATURE);
|
||||
#else
|
||||
Extruder::setTemperatureForExtruder(actTemp[Extruder::current->id], Extruder::current->id, false, actTemp[Extruder::current->id] > MAX_ROOM_TEMPERATURE);
|
||||
#endif
|
||||
if(Z_HOME_DIR < 0) startZ = Printer::zMin;
|
||||
else startZ = Printer::zMin + Printer::zLength - zBedOffset;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -1880,9 +1944,9 @@ void Printer::showConfiguration() {
|
|||
|
||||
Distortion Printer::distortion;
|
||||
|
||||
void Printer::measureDistortion(void)
|
||||
bool Printer::measureDistortion(void)
|
||||
{
|
||||
distortion.measure();
|
||||
return distortion.measure();
|
||||
}
|
||||
|
||||
Distortion::Distortion()
|
||||
|
@ -1908,9 +1972,9 @@ void Distortion::updateDerived()
|
|||
step = (2 * Printer::axisStepsPerMM[Z_AXIS] * DISTORTION_CORRECTION_R) / (DISTORTION_CORRECTION_POINTS - 1.0f);
|
||||
radiusCorrectionSteps = DISTORTION_CORRECTION_R * Printer::axisStepsPerMM[Z_AXIS];
|
||||
#else
|
||||
xCorrectionSteps = (DISTORTION_XMAX - DISTORTION_XMIN) * Printer::axisStepsPerMM[X_AXIS] / DISTORTION_CORRECTION_POINTS;
|
||||
xCorrectionSteps = (DISTORTION_XMAX - DISTORTION_XMIN) * Printer::axisStepsPerMM[X_AXIS] / (DISTORTION_CORRECTION_POINTS - 1);
|
||||
xOffsetSteps = DISTORTION_XMIN * Printer::axisStepsPerMM[X_AXIS];
|
||||
yCorrectionSteps = (DISTORTION_YMAX - DISTORTION_YMIN) * Printer::axisStepsPerMM[Y_AXIS] / DISTORTION_CORRECTION_POINTS;
|
||||
yCorrectionSteps = (DISTORTION_YMAX - DISTORTION_YMIN) * Printer::axisStepsPerMM[Y_AXIS] / (DISTORTION_CORRECTION_POINTS - 1);
|
||||
yOffsetSteps = DISTORTION_YMIN * Printer::axisStepsPerMM[Y_AXIS];
|
||||
|
||||
#endif
|
||||
|
@ -2006,7 +2070,7 @@ void Distortion::extrapolateCorners()
|
|||
extrapolateCorner(m, m,-1,-1);
|
||||
}
|
||||
|
||||
void Distortion::measure(void)
|
||||
bool Distortion::measure(void)
|
||||
{
|
||||
fast8_t ix, iy;
|
||||
float z = EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0);
|
||||
|
@ -2020,6 +2084,7 @@ void Distortion::measure(void)
|
|||
#if Z_HOME_DIR < 0 && Z_PROBE_Z_OFFSET_MODE == 1
|
||||
zCorrection += Printer::zBedOffset * Printer::axisStepsPerMM[Z_AXIS];
|
||||
#endif
|
||||
Printer::startProbing(true);
|
||||
for (iy = DISTORTION_CORRECTION_POINTS - 1; iy >= 0; iy--)
|
||||
for (ix = 0; ix < DISTORTION_CORRECTION_POINTS; ix++)
|
||||
{
|
||||
|
@ -2031,23 +2096,23 @@ void Distortion::measure(void)
|
|||
float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * step - radiusCorrectionSteps);
|
||||
#else
|
||||
float mtx = Printer::invAxisStepsPerMM[X_AXIS] * (ix * xCorrectionSteps + xOffsetSteps);
|
||||
float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * xCorrectionSteps + yOffsetSteps);
|
||||
float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * yCorrectionSteps + yOffsetSteps);
|
||||
#endif
|
||||
//Com::printF(PSTR("mx "),mtx);
|
||||
//Com::printF(PSTR("my "),mty);
|
||||
//Com::printF(PSTR("ix "),(int)ix);
|
||||
//Com::printFLN(PSTR("iy "),(int)iy);
|
||||
Printer::moveToReal(mtx, mty, z, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
#if DISTORTION_EXTRAPOLATE_CORNERS && DRIVE_SYSTEM == DELTA
|
||||
setMatrix(floor(0.5f + Printer::axisStepsPerMM[Z_AXIS] * (z -
|
||||
Printer::runZProbe(ix == 1 && iy == DISTORTION_CORRECTION_POINTS - 1, ix == DISTORTION_CORRECTION_POINTS - 2 && iy == 0, Z_PROBE_REPETITIONS))) + zCorrection,
|
||||
matrixIndex(ix,iy));
|
||||
#else
|
||||
setMatrix(floor(0.5f + Printer::axisStepsPerMM[Z_AXIS] * (z -
|
||||
Printer::runZProbe(ix == 0 && iy == DISTORTION_CORRECTION_POINTS - 1, ix == DISTORTION_CORRECTION_POINTS - 1 && iy == 0, Z_PROBE_REPETITIONS))) + zCorrection,
|
||||
matrixIndex(ix,iy));
|
||||
#endif
|
||||
float zp = Printer::runZProbe(false,false, Z_PROBE_REPETITIONS);
|
||||
if(zp == ILLEGAL_Z_PROBE) {
|
||||
Com::printErrorFLN(PSTR("Stopping distortion measurement due to errors."));
|
||||
Printer::finishProbing();
|
||||
return false;
|
||||
}
|
||||
setMatrix(floor(0.5f + Printer::axisStepsPerMM[Z_AXIS] * (z -zp)) + zCorrection,
|
||||
matrixIndex(ix,iy));
|
||||
}
|
||||
Printer::finishProbing();
|
||||
#if (DRIVE_SYSTEM == DELTA) && DISTORTION_EXTRAPOLATE_CORNERS
|
||||
extrapolateCorners();
|
||||
#endif
|
||||
|
@ -2076,12 +2141,13 @@ void Distortion::measure(void)
|
|||
}
|
||||
showMatrix();
|
||||
enable(true);
|
||||
return true;
|
||||
//Printer::homeAxis(false, false, true);
|
||||
}
|
||||
|
||||
int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const
|
||||
{
|
||||
if (!enabled || z > zEnd || Printer::isZProbingActive()) return 0.0f;
|
||||
if (!enabled || z > zEnd || Printer::isZProbingActive()) return 0;
|
||||
if(false && z == 0) {
|
||||
Com::printF(PSTR("correcting ("), x); Com::printF(PSTR(","), y);
|
||||
}
|
||||
|
@ -2136,7 +2202,8 @@ int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const
|
|||
Com::printF(PSTR(" iy= "), fyFloor); Com::printFLN(PSTR(" fy= "), fy);
|
||||
}
|
||||
if (z > zStart && z > 0)
|
||||
correction_z *= (zEnd - z) / (zEnd - zStart);
|
||||
//All variables are type int. For calculation we need float values
|
||||
correction_z = (correction_z * static_cast<float>(zEnd - z) / (zEnd - zStart));
|
||||
/* if(correction_z > 20 || correction_z < -20) {
|
||||
Com::printFLN(PSTR("Corr. error too big:"),correction_z);
|
||||
Com::printF(PSTR("fxf"),(int)fxFloor);
|
||||
|
@ -2183,9 +2250,9 @@ void Distortion::showMatrix() {
|
|||
#endif
|
||||
int32_t idx = matrixIndex(ix, iy);
|
||||
float z = getMatrix(idx) * Printer::invAxisStepsPerMM[Z_AXIS];
|
||||
Com::printF(PSTR("Distortion correction at px:"),x,2);
|
||||
Com::printF(PSTR(" py:"),y,2);
|
||||
Com::printFLN(PSTR(" zCoorection:"),z,3);
|
||||
Com::printF(PSTR("G33 X"),x,2);
|
||||
Com::printF(PSTR(" Y"),y,2);
|
||||
Com::printFLN(PSTR(" Z"),z,3);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2289,7 +2356,7 @@ void Printer::showJSONStatus(int type) {
|
|||
Com::printF(PSTR(",\"coldExtrudeTemp\":0,\"coldRetractTemp\":0.0,\"geometry\":\""));
|
||||
#if (DRIVE_SYSTEM == DELTA)
|
||||
Com::printF(PSTR("delta"));
|
||||
#elif (DRIVE_SYSTEM == CARTESIAN)
|
||||
#elif (DRIVE_SYSTEM == CARTESIAN || DRIVE_SYSTEM == GANTRY_FAKE)
|
||||
Com::printF(PSTR("cartesian"));
|
||||
#elif ((DRIVE_SYSTEM == XY_GANTRY) || (DRIVE_SYSTEM == YX_GANTRY))
|
||||
Com::printF(PSTR("coreXY"));
|
||||
|
@ -2308,7 +2375,7 @@ void Printer::showJSONStatus(int type) {
|
|||
Com::print('}');
|
||||
firstOccurrence = false;
|
||||
}
|
||||
Com::printFLN(PSTR("]"));
|
||||
Com::printF(PSTR("]"));
|
||||
break;
|
||||
case 3:
|
||||
Com::printF(PSTR(",\"currentLayer\":"));
|
||||
|
@ -2319,7 +2386,7 @@ void Printer::showJSONStatus(int type) {
|
|||
#else
|
||||
Com::printF(PSTR("-1"));
|
||||
#endif
|
||||
Com::printF(PSTR("\",extrRaw\":["));
|
||||
Com::printF(PSTR(",\"extrRaw\":["));
|
||||
firstOccurrence = true;
|
||||
for (int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
if (!firstOccurrence) Com::print(',');
|
||||
|
@ -2394,7 +2461,7 @@ void Printer::showJSONStatus(int type) {
|
|||
Com::print(',');
|
||||
Com::print(extruder[i].maxFeedrate);
|
||||
}
|
||||
Com::printFLN(PSTR("]"));
|
||||
Com::printF(PSTR("]"));
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
|
@ -93,7 +93,7 @@ union wizardVar
|
|||
#define PRINTER_FLAG2_IGNORE_M106_COMMAND 8
|
||||
#define PRINTER_FLAG2_DEBUG_JAM 16
|
||||
#define PRINTER_FLAG2_JAMCONTROL_DISABLED 32
|
||||
#define PRINTER_FLAG2_HOMING 64
|
||||
#define PRINTER_FLAG2_HOMING 64
|
||||
#define PRINTER_FLAG2_ALL_E_MOTORS 128 // Set all e motors flag
|
||||
|
||||
// List of possible interrupt events (1-255 allowed)
|
||||
|
@ -115,6 +115,14 @@ union wizardVar
|
|||
#define towerBMinSteps Printer::yMinSteps
|
||||
#define towerCMinSteps Printer::zMinSteps
|
||||
|
||||
class Plane {
|
||||
public:
|
||||
// f(x, y) = ax + by + c
|
||||
float a,b,c;
|
||||
float z(float x,float y) {
|
||||
return a * x + y * b + c;
|
||||
}
|
||||
};
|
||||
#if DISTORTION_CORRECTION
|
||||
class Distortion
|
||||
{
|
||||
|
@ -123,7 +131,7 @@ public:
|
|||
void init();
|
||||
void enable(bool permanent = true);
|
||||
void disable(bool permanent = true);
|
||||
void measure(void);
|
||||
bool measure(void);
|
||||
int32_t correct(int32_t x, int32_t y, int32_t z) const;
|
||||
void updateDerived();
|
||||
void reportStatus();
|
||||
|
@ -187,7 +195,15 @@ public:
|
|||
static void update();
|
||||
static void report();
|
||||
static INLINE bool anyXYZMax() {
|
||||
return (lastState & (ENDSTOP_X_MAX_ID|ENDSTOP_Z_MAX_ID|ENDSTOP_Z_MAX_ID)) != 0;
|
||||
return (lastState & (ENDSTOP_X_MAX_ID|ENDSTOP_Y_MAX_ID|ENDSTOP_Z_MAX_ID)) != 0;
|
||||
}
|
||||
static INLINE bool anyXYZ() {
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
return (lastState & (ENDSTOP_X_MAX_ID|ENDSTOP_Y_MAX_ID|ENDSTOP_Z_MAX_ID|ENDSTOP_X_MIN_ID|ENDSTOP_Y_MIN_ID|ENDSTOP_Z_MIN_ID|ENDSTOP_Z2_MIN_ID)) != 0 ||
|
||||
lastState2 != 0;
|
||||
#else
|
||||
return (lastState & (ENDSTOP_X_MAX_ID|ENDSTOP_Y_MAX_ID|ENDSTOP_Z_MAX_ID|ENDSTOP_X_MIN_ID|ENDSTOP_Y_MIN_ID|ENDSTOP_Z_MIN_ID|ENDSTOP_Z2_MIN_ID)) != 0;
|
||||
#endif
|
||||
}
|
||||
static INLINE void resetAccumulator() {
|
||||
accumulator = 0;
|
||||
|
@ -258,18 +274,18 @@ public:
|
|||
#endif
|
||||
}
|
||||
};
|
||||
|
||||
#ifndef DEFAULT_PRINTER_MODE
|
||||
#if NUM_EXTRUDER > 0
|
||||
#define DEFAULT_PRINTER_MODE PRINTER_MODE_FFF
|
||||
#elif defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
#define DEFAULT_PRINTER_MODE PRINTER_MODE_LASER
|
||||
#elif defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
#define DEFAULT_PRINTER_MODE PRINTER_MODE_CNC
|
||||
#else
|
||||
#error No supported printer mode compiled
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_PRINTER_MODE
|
||||
#if NUM_EXTRUDER > 0
|
||||
#define DEFAULT_PRINTER_MODE PRINTER_MODE_FFF
|
||||
#elif defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
#define DEFAULT_PRINTER_MODE PRINTER_MODE_LASER
|
||||
#elif defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
#define DEFAULT_PRINTER_MODE PRINTER_MODE_CNC
|
||||
#else
|
||||
#error No supported printer mode compiled
|
||||
#endif
|
||||
#endif
|
||||
|
||||
class Printer
|
||||
{
|
||||
|
@ -296,8 +312,8 @@ public:
|
|||
static uint8_t relativeCoordinateMode; ///< Determines absolute (false) or relative Coordinates (true).
|
||||
static uint8_t relativeExtruderCoordinateMode; ///< Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
|
||||
|
||||
static uint8_t unitIsInches;
|
||||
static uint8_t mode;
|
||||
static uint8_t unitIsInches;
|
||||
static uint8_t mode;
|
||||
static uint8_t fanSpeed; // Last fan speed set with M106/M107
|
||||
static float zBedOffset;
|
||||
static uint8_t flag0,flag1; // 1 = stepper disabled, 2 = use external extruder interrupt, 4 = temp Sensor defect, 8 = homed
|
||||
|
@ -315,7 +331,7 @@ public:
|
|||
static float extrusionFactor; ///< Extrusion multiply factor
|
||||
#if NONLINEAR_SYSTEM
|
||||
static int32_t maxDeltaPositionSteps;
|
||||
static int32_t currentDeltaPositionSteps[E_TOWER_ARRAY];
|
||||
static int32_t currentNonlinearPositionSteps[E_TOWER_ARRAY];
|
||||
static floatLong deltaDiagonalStepsSquaredA;
|
||||
static floatLong deltaDiagonalStepsSquaredB;
|
||||
static floatLong deltaDiagonalStepsSquaredC;
|
||||
|
@ -331,7 +347,8 @@ public:
|
|||
static int16_t travelMovesPerSecond;
|
||||
static int16_t printMovesPerSecond;
|
||||
static float radius0;
|
||||
#else
|
||||
#endif
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
static int32_t zCorrectionStepsIncluded;
|
||||
#endif
|
||||
#if FEATURE_Z_PROBE || MAX_HARDWARE_ENDSTOP_Z || NONLINEAR_SYSTEM
|
||||
|
@ -393,7 +410,7 @@ public:
|
|||
static float memoryZ;
|
||||
static float memoryE;
|
||||
static float memoryF;
|
||||
#if GANTRY
|
||||
#if GANTRY && !defined(FAST_COREXYZ)
|
||||
static int8_t motorX;
|
||||
static int8_t motorYorZ;
|
||||
#endif
|
||||
|
@ -433,6 +450,7 @@ public:
|
|||
static void toggleDryRun();
|
||||
static void toggleCommunication();
|
||||
static void toggleNoMoves();
|
||||
static void toggleEndStop();
|
||||
static INLINE uint8_t getDebugLevel() {return debugLevel;}
|
||||
static INLINE bool debugEcho()
|
||||
{
|
||||
|
@ -464,6 +482,11 @@ public:
|
|||
return ((debugLevel & 32) != 0);
|
||||
}
|
||||
|
||||
static INLINE bool debugEndStop()
|
||||
{
|
||||
return ((debugLevel & 64) != 0);
|
||||
}
|
||||
|
||||
static INLINE bool debugFlag(uint8_t flags)
|
||||
{
|
||||
return (debugLevel & flags);
|
||||
|
@ -477,7 +500,7 @@ public:
|
|||
static INLINE void debugReset(uint8_t flags)
|
||||
{
|
||||
setDebugLevel(debugLevel & ~flags);
|
||||
}
|
||||
}
|
||||
/** Sets the pwm for the fan speed. Gets called by motion control ot Commands::setFanSpeed. */
|
||||
static void setFanSpeedDirectly(uint8_t speed);
|
||||
static void setFan2SpeedDirectly(uint8_t speed);
|
||||
|
@ -487,7 +510,7 @@ public:
|
|||
#if (X_ENABLE_PIN > -1)
|
||||
WRITE(X_ENABLE_PIN, !X_ENABLE_ON);
|
||||
#endif
|
||||
#if FEATURE_TWO_XSTEPPER && (X2_ENABLE_PIN > -1)
|
||||
#if (FEATURE_TWO_XSTEPPER || DUAL_X_AXIS) && (X2_ENABLE_PIN > -1)
|
||||
WRITE(X2_ENABLE_PIN, !X_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
|
@ -522,7 +545,7 @@ public:
|
|||
#if (X_ENABLE_PIN > -1)
|
||||
WRITE(X_ENABLE_PIN, X_ENABLE_ON);
|
||||
#endif
|
||||
#if FEATURE_TWO_XSTEPPER && (X2_ENABLE_PIN > -1)
|
||||
#if (FEATURE_TWO_XSTEPPER || DUAL_X_AXIS) && (X2_ENABLE_PIN > -1)
|
||||
WRITE(X2_ENABLE_PIN, X_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
|
@ -556,14 +579,14 @@ public:
|
|||
if(positive)
|
||||
{
|
||||
WRITE(X_DIR_PIN,!INVERT_X_DIR);
|
||||
#if FEATURE_TWO_XSTEPPER
|
||||
#if FEATURE_TWO_XSTEPPER || DUAL_X_AXIS
|
||||
WRITE(X2_DIR_PIN,!INVERT_X_DIR);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
WRITE(X_DIR_PIN,INVERT_X_DIR);
|
||||
#if FEATURE_TWO_XSTEPPER
|
||||
#if FEATURE_TWO_XSTEPPER || DUAL_X_AXIS
|
||||
WRITE(X2_DIR_PIN,INVERT_X_DIR);
|
||||
#endif
|
||||
}
|
||||
|
@ -816,7 +839,7 @@ public:
|
|||
{
|
||||
flag0 &= ~PRINTER_FLAG0_STEPPER_DISABLED;
|
||||
#if FAN_BOARD_PIN > -1
|
||||
pwm_pos[PWM_BOARD_FAN] = 255;
|
||||
pwm_pos[PWM_BOARD_FAN] = BOARD_FAN_SPEED;
|
||||
#endif // FAN_BOARD_PIN
|
||||
}
|
||||
static INLINE bool isAnyTempsensorDefect()
|
||||
|
@ -826,6 +849,7 @@ public:
|
|||
static INLINE void setAnyTempsensorDefect()
|
||||
{
|
||||
flag0 |= PRINTER_FLAG0_TEMPSENSOR_DEFECT;
|
||||
debugSet(8);
|
||||
}
|
||||
static INLINE void unsetAnyTempsensorDefect()
|
||||
{
|
||||
|
@ -854,7 +878,7 @@ public:
|
|||
}
|
||||
static INLINE void executeXYGantrySteps()
|
||||
{
|
||||
#if (GANTRY)
|
||||
#if (GANTRY) && !defined(FAST_COREXYZ)
|
||||
if(motorX <= -2)
|
||||
{
|
||||
WRITE(X_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
|
@ -891,7 +915,7 @@ public:
|
|||
}
|
||||
static INLINE void executeXZGantrySteps()
|
||||
{
|
||||
#if (GANTRY)
|
||||
#if (GANTRY) && !defined(FAST_COREXYZ)
|
||||
if(motorX <= -2)
|
||||
{
|
||||
WRITE(X_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
|
@ -910,7 +934,6 @@ public:
|
|||
}
|
||||
if(motorYorZ <= -2)
|
||||
{
|
||||
//ANALYZER_ON(ANALYZER_CH3); // I dont think i can use these as they are for the y - possible bug area though
|
||||
WRITE(Z_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
#if FEATURE_TWO_ZSTEPPER
|
||||
WRITE(Z2_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
|
@ -922,7 +945,6 @@ public:
|
|||
}
|
||||
else if(motorYorZ >= 2)
|
||||
{
|
||||
//ANALYZER_ON(ANALYZER_CH3); // I dont think i can use these as they are for the y - possible bug area though
|
||||
WRITE(Z_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
#if FEATURE_TWO_ZSTEPPER
|
||||
WRITE(Z2_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
|
@ -936,9 +958,24 @@ public:
|
|||
}
|
||||
static INLINE void startXStep()
|
||||
{
|
||||
#if DUAL_X_AXIS
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
if(Extruder::dittoMode) {
|
||||
WRITE(X_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if(Extruder::current->id) {
|
||||
WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
} else {
|
||||
WRITE(X_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
}
|
||||
#else
|
||||
WRITE(X_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
#if FEATURE_TWO_XSTEPPER
|
||||
WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
static INLINE void startYStep()
|
||||
|
@ -961,7 +998,7 @@ public:
|
|||
static INLINE void endXYZSteps()
|
||||
{
|
||||
WRITE(X_STEP_PIN,!START_STEP_WITH_HIGH);
|
||||
#if FEATURE_TWO_XSTEPPER
|
||||
#if FEATURE_TWO_XSTEPPER || DUAL_X_AXIS
|
||||
WRITE(X2_STEP_PIN,!START_STEP_WITH_HIGH);
|
||||
#endif
|
||||
WRITE(Y_STEP_PIN,!START_STEP_WITH_HIGH);
|
||||
|
@ -1075,9 +1112,9 @@ public:
|
|||
#if NONLINEAR_SYSTEM
|
||||
static INLINE void setDeltaPositions(long xaxis, long yaxis, long zaxis)
|
||||
{
|
||||
currentDeltaPositionSteps[A_TOWER] = xaxis;
|
||||
currentDeltaPositionSteps[B_TOWER] = yaxis;
|
||||
currentDeltaPositionSteps[C_TOWER] = zaxis;
|
||||
currentNonlinearPositionSteps[A_TOWER] = xaxis;
|
||||
currentNonlinearPositionSteps[B_TOWER] = yaxis;
|
||||
currentNonlinearPositionSteps[C_TOWER] = zaxis;
|
||||
}
|
||||
static void deltaMoveToTopEndstops(float feedrate);
|
||||
#endif
|
||||
|
@ -1093,14 +1130,15 @@ public:
|
|||
#endif
|
||||
// Moved outside FEATURE_Z_PROBE to allow auto-level functional test on
|
||||
// system without Z-probe
|
||||
#if FEATURE_AUTOLEVEL
|
||||
static void transformToPrinter(float x,float y,float z,float &transX,float &transY,float &transZ);
|
||||
static void transformFromPrinter(float x,float y,float z,float &transX,float &transY,float &transZ);
|
||||
#if FEATURE_AUTOLEVEL
|
||||
static void resetTransformationMatrix(bool silent);
|
||||
static void buildTransformationMatrix(float h1,float h2,float h3);
|
||||
//static void buildTransformationMatrix(float h1,float h2,float h3);
|
||||
static void buildTransformationMatrix(Plane &plane);
|
||||
#endif
|
||||
#if DISTORTION_CORRECTION
|
||||
static void measureDistortion(void);
|
||||
static bool measureDistortion(void);
|
||||
static Distortion distortion;
|
||||
#endif
|
||||
static void MemoryPosition();
|
||||
|
@ -1121,11 +1159,10 @@ public:
|
|||
}
|
||||
static void showConfiguration();
|
||||
static void setCaseLight(bool on);
|
||||
static void reportCaseLightStatus();
|
||||
#if JSON_OUTPUT
|
||||
static void showJSONStatus(int type);
|
||||
static void reportCaseLightStatus();
|
||||
#if JSON_OUTPUT
|
||||
static void showJSONStatus(int type);
|
||||
#endif
|
||||
private:
|
||||
static void homeXAxis();
|
||||
static void homeYAxis();
|
||||
static void homeZAxis();
|
||||
|
|
|
@ -24,27 +24,29 @@
|
|||
|
||||
#include <math.h>
|
||||
#include <stdint.h>
|
||||
#define REPETIER_VERSION "0.92.8"
|
||||
#define REPETIER_VERSION "0.92.9"
|
||||
|
||||
// ##########################################################################################
|
||||
// ## Debug configuration ##
|
||||
// ##########################################################################################
|
||||
// These are run time sqitchable debug flags
|
||||
// These are run time switchable debug flags
|
||||
enum debugFlags {DEB_ECHO = 0x1, DEB_INFO = 0x2, DEB_ERROR = 0x4,DEB_DRYRUN = 0x8,
|
||||
DEB_COMMUNICATION = 0x10, DEB_NOMOVES = 0x20, DEB_DEBUG = 0x40
|
||||
};
|
||||
|
||||
/** Uncomment, to see detailed data for every move. Only for debugging purposes! */
|
||||
//#define DEBUG_QUEUE_MOVE
|
||||
/** write infos about path planner changes */
|
||||
//#define DEBUG_PLANNER
|
||||
/** Allows M111 to set bit 5 (16) which disables all commands except M111. This can be used
|
||||
to test your data througput or search for communication problems. */
|
||||
to test your data throughput or search for communication problems. */
|
||||
#define INCLUDE_DEBUG_COMMUNICATION 1
|
||||
/** Allows M111 so set bit 6 (32) which disables moves, at the first tried step. In combination
|
||||
with a dry run, you can test the speed of path computations, which are still performed. */
|
||||
#define INCLUDE_DEBUG_NO_MOVE 1
|
||||
/** Writes the free RAM to output, if it is less then at the last test. Should always return
|
||||
values >500 for safety, since it doesn't catch every function call. Nice to tweak cache
|
||||
usage or for seraching for memory induced errors. Switch it off for production, it costs execution time. */
|
||||
usage or for searching for memory induced errors. Switch it off for production, it costs execution time. */
|
||||
//#define DEBUG_FREE_MEMORY
|
||||
//#define DEBUG_ADVANCE
|
||||
/** If enabled, writes the created generic table to serial port at startup. */
|
||||
|
@ -53,7 +55,7 @@ usage or for seraching for memory induced errors. Switch it off for production,
|
|||
//#define DEBUG_STEPCOUNT
|
||||
/** This enables code to make M666 drop an ok, so you get problems with communication. It is to test host robustness. */
|
||||
//#define DEBUG_COM_ERRORS
|
||||
/** Adds a menu point in quick settings to write debg informations to the host in case of hangs where the ui still works. */
|
||||
/** Adds a menu point in quick settings to write debug informations to the host in case of hangs where the ui still works. */
|
||||
//#define DEBUG_PRINT
|
||||
//#define DEBUG_DELTA_OVERFLOW
|
||||
//#define DEBUG_DELTA_REALPOS
|
||||
|
@ -76,6 +78,7 @@ usage or for seraching for memory induced errors. Switch it off for production,
|
|||
#define BIPOD 5
|
||||
#define XZ_GANTRY 8
|
||||
#define ZX_GANTRY 9
|
||||
#define GANTRY_FAKE 10
|
||||
|
||||
#define WIZARD_STACK_SIZE 8
|
||||
#define IGNORE_COORDINATE 999999
|
||||
|
@ -130,6 +133,7 @@ usage or for seraching for memory induced errors. Switch it off for production,
|
|||
#define HOME_ORDER_ZXY 5
|
||||
#define HOME_ORDER_ZYX 6
|
||||
#define HOME_ORDER_ZXYTZ 7 // Needs hot hotend for correct homing
|
||||
#define HOME_ORDER_XYTZ 8 // Needs hot hotend for correct homing
|
||||
|
||||
#define NO_CONTROLLER 0
|
||||
#define UICONFIG_CONTROLLER 1
|
||||
|
@ -155,6 +159,7 @@ usage or for seraching for memory induced errors. Switch it off for production,
|
|||
#define CONTROLLER_VIKI2 21
|
||||
#define CONTROLLER_LCD_MP_PHARAOH_DUE 22
|
||||
#define CONTROLLER_SPARKLCD_ADAPTER 23
|
||||
#define CONTROLLER_ZONESTAR 24
|
||||
#define CONTROLLER_FELIX_DUE 405
|
||||
|
||||
//direction flags
|
||||
|
@ -179,16 +184,68 @@ usage or for seraching for memory induced errors. Switch it off for production,
|
|||
|
||||
// add pid control
|
||||
#define TEMP_PID 1
|
||||
|
||||
#define PRINTER_MODE_FFF 0
|
||||
#define PRINTER_MODE_LASER 1
|
||||
#define PRINTER_MODE_CNC 2
|
||||
// we can not prevent this as some configs need a parameter and others not
|
||||
|
||||
#define PRINTER_MODE_FFF 0
|
||||
#define PRINTER_MODE_LASER 1
|
||||
#define PRINTER_MODE_CNC 2
|
||||
|
||||
#define ILLEGAL_Z_PROBE -888
|
||||
|
||||
// we can not prevent this as some configurations need a parameter and others not
|
||||
#pragma GCC diagnostic ignored "-Wunused-parameter"
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
|
||||
#include "Configuration.h"
|
||||
|
||||
#ifndef SHARED_EXTRUDER_HEATER
|
||||
#define SHARED_EXTRUDER_HEATER 0
|
||||
#endif
|
||||
|
||||
#ifndef DUAL_X_AXIS
|
||||
#define DUAL_X_AXIS 0
|
||||
#endif
|
||||
|
||||
#if SHARED_EXTRUDER_HEATER || MIXING_EXTRUDER
|
||||
#undef EXT1_HEATER_PIN
|
||||
#undef EXT2_HEATER_PIN
|
||||
#undef EXT3_HEATER_PIN
|
||||
#undef EXT4_HEATER_PIN
|
||||
#undef EXT5_HEATER_PIN
|
||||
#define EXT1_HEATER_PIN -1
|
||||
#define EXT2_HEATER_PIN -1
|
||||
#define EXT3_HEATER_PIN -1
|
||||
#define EXT4_HEATER_PIN -1
|
||||
#define EXT5_HEATER_PIN -1
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_FAN_SPEED
|
||||
#define BOARD_FAN_SPEED
|
||||
#endif
|
||||
|
||||
#ifndef MAX_JERK_DISTANCE
|
||||
#define MAX_JERK_DISTANCE 0.6
|
||||
#endif
|
||||
#define XY_GANTRY 1
|
||||
#define YX_GANTRY 2
|
||||
#define DELTA 3
|
||||
#define TUGA 4
|
||||
#define BIPOD 5
|
||||
#define XZ_GANTRY 8
|
||||
#define ZX_GANTRY 9
|
||||
#if defined(FAST_COREXYZ) && !(DRIVE_SYSTEM==XY_GANTRY || DRIVE_SYSTEM==YX_GANTRY || DRIVE_SYSTEM==XZ_GANTRY || DRIVE_SYSTEM==ZX_GANTRY || DRIVE_SYSTEM==GANTRY_FAKE)
|
||||
#undef FAST_COREXYZ
|
||||
#endif
|
||||
#ifdef FAST_COREXYZ
|
||||
#if DELTA_SEGMENTS_PER_SECOND_PRINT < 30
|
||||
#undef DELTA_SEGMENTS_PER_SECOND_PRINT
|
||||
#define DELTA_SEGMENTS_PER_SECOND_PRINT 30 // core is linear, no subsegments needed
|
||||
#endif
|
||||
#if DELTA_SEGMENTS_PER_SECOND_MOVE < 30
|
||||
#undef DELTA_SEGMENTS_PER_SECOND_MOVE
|
||||
#define DELTA_SEGMENTS_PER_SECOND_MOVE 30
|
||||
#endif
|
||||
#endif
|
||||
|
||||
inline void memcopy2(void *dest,void *source) {
|
||||
*((int16_t*)dest) = *((int16_t*)source);
|
||||
}
|
||||
|
@ -200,6 +257,10 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define JSON_OUTPUT 0
|
||||
#endif
|
||||
|
||||
#if !defined(ZPROBE_MIN_TEMPERATURE) && defined(ZHOME_MIN_TEMPERATURE)
|
||||
#define ZPROBE_MIN_TEMPERATURE ZHOME_MIN_TEMPERATURE
|
||||
#endif
|
||||
|
||||
#if FEATURE_Z_PROBE && Z_PROBE_PIN < 0
|
||||
#error You need to define Z_PROBE_PIN to use z probe!
|
||||
#endif
|
||||
|
@ -220,7 +281,7 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define ZHOME_Y_POS IGNORE_COORDINATE
|
||||
#endif
|
||||
|
||||
// MS1 MS2 Stepper Driver Microstepping mode table
|
||||
// MS1 MS2 Stepper Driver Micro stepping mode table
|
||||
#define MICROSTEP1 LOW,LOW
|
||||
#define MICROSTEP2 HIGH,LOW
|
||||
#define MICROSTEP4 LOW,HIGH
|
||||
|
@ -256,7 +317,7 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define SOFTWARE_LEVELING (defined(FEATURE_SOFTWARE_LEVELING) && (DRIVE_SYSTEM==DELTA))
|
||||
/** \brief Horizontal distance bridged by the diagonal push rod when the end effector is in the center. It is pretty close to 50% of the push rod length (250 mm).
|
||||
*/
|
||||
#ifndef ROD_RADIUS
|
||||
#if !defined(ROD_RADIUS) && DRIVE_SYSTEM == DELTA
|
||||
#define ROD_RADIUS (PRINTER_RADIUS-END_EFFECTOR_HORIZONTAL_OFFSET-CARRIAGE_HORIZONTAL_OFFSET)
|
||||
#endif
|
||||
|
||||
|
@ -264,7 +325,7 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define UI_SPEEDDEPENDENT_POSITIONING true
|
||||
#endif
|
||||
|
||||
#if DRIVE_SYSTEM==DELTA || DRIVE_SYSTEM==TUGA || DRIVE_SYSTEM==BIPOD
|
||||
#if DRIVE_SYSTEM==DELTA || DRIVE_SYSTEM==TUGA || DRIVE_SYSTEM==BIPOD || defined(FAST_COREXYZ)
|
||||
#define NONLINEAR_SYSTEM 1
|
||||
#else
|
||||
#define NONLINEAR_SYSTEM 0
|
||||
|
@ -274,16 +335,16 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define MANUAL_CONTROL 1
|
||||
#endif
|
||||
|
||||
#define GANTRY ( DRIVE_SYSTEM==XY_GANTRY || DRIVE_SYSTEM==YX_GANTRY || DRIVE_SYSTEM==XZ_GANTRY || DRIVE_SYSTEM==ZX_GANTRY)
|
||||
#define GANTRY ( DRIVE_SYSTEM==XY_GANTRY || DRIVE_SYSTEM==YX_GANTRY || DRIVE_SYSTEM==XZ_GANTRY || DRIVE_SYSTEM==ZX_GANTRY || DRIVE_SYSTEM==GANTRY_FAKE)
|
||||
|
||||
//Step to split a cirrcle in small Lines
|
||||
//Step to split a circle in small Lines
|
||||
#ifndef MM_PER_ARC_SEGMENT
|
||||
#define MM_PER_ARC_SEGMENT 1
|
||||
#define MM_PER_ARC_SEGMENT_BIG 3
|
||||
#else
|
||||
#define MM_PER_ARC_SEGMENT_BIG MM_PER_ARC_SEGMENT
|
||||
#endif
|
||||
//After this count of steps a new SIN / COS caluclation is startet to correct the circle interpolation
|
||||
//After this count of steps a new SIN / COS calculation is started to correct the circle interpolation
|
||||
#define N_ARC_CORRECTION 25
|
||||
|
||||
// Test for shared cooler
|
||||
|
@ -330,9 +391,9 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#else
|
||||
#define EXTRUDER_JAM_CONTROL 0
|
||||
#endif
|
||||
#ifndef JAM_METHOD
|
||||
#define JAM_METHOD 1
|
||||
#endif
|
||||
#ifndef JAM_METHOD
|
||||
#define JAM_METHOD 1
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER > 0 && EXT0_TEMPSENSOR_TYPE < 101
|
||||
#define EXT0_ANALOG_INPUTS 1
|
||||
|
@ -358,7 +419,7 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define EXT1_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER > 2 && EXT2_TEMPSENSOR_TYPE<101
|
||||
#if NUM_EXTRUDER > 2 && EXT2_TEMPSENSOR_TYPE < 101
|
||||
#define EXT2_ANALOG_INPUTS 1
|
||||
#define EXT2_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS
|
||||
#define EXT2_ANALOG_CHANNEL ACCOMMA1 EXT2_TEMPSENSOR_PIN
|
||||
|
@ -394,7 +455,7 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define EXT4_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER > 5 && EXT5_TEMPSENSOR_TYPE<101
|
||||
#if NUM_EXTRUDER > 5 && EXT5_TEMPSENSOR_TYPE < 101
|
||||
#define EXT5_ANALOG_INPUTS 1
|
||||
#define EXT5_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS
|
||||
#define EXT5_ANALOG_CHANNEL ACCOMMA4 EXT5_TEMPSENSOR_PIN
|
||||
|
@ -406,11 +467,10 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define EXT5_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if HAVE_HEATED_BED && HEATED_BED_SENSOR_TYPE<101
|
||||
#if HAVE_HEATED_BED && HEATED_BED_SENSOR_TYPE < 101
|
||||
#define BED_ANALOG_INPUTS 1
|
||||
#define BED_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS
|
||||
#define BED_ANALOG_CHANNEL ACCOMMA5 HEATED_BED_SENSOR_PIN
|
||||
#undef BEKOMMA
|
||||
#define BED_KOMMA ,
|
||||
#else
|
||||
#define BED_ANALOG_INPUTS 0
|
||||
|
@ -423,9 +483,20 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#define THERMO_ANALOG_INPUTS 1
|
||||
#define THERMO_ANALOG_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS
|
||||
#define THERMO_ANALOG_CHANNEL BED_KOMMA FAN_THERMO_THERMISTOR_PIN
|
||||
#define THERMO_COMMA ,
|
||||
#else
|
||||
#define THERMO_ANALOG_INPUTS 0
|
||||
#define THERMO_ANALOG_CHANNEL
|
||||
#define THERMO_COMMA BED_KOMMA
|
||||
#endif
|
||||
|
||||
#if defined(ADC_KEYPAD_PIN) && (ADC_KEYPAD_PIN > -1)
|
||||
#define KEYPAD_ANALOG_INPUTS 1
|
||||
#define KEYPAD_ANALOG_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS+THERMO_ANALOG_INPUTS
|
||||
#define KEYPAD_ANALOG_CHANNEL THERMO_COMMA ADC_KEYPAD_PIN
|
||||
#else
|
||||
#define KEYPAD_ANALOG_INPUTS 0
|
||||
#define KEYPAD_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#ifndef DEBUG_FREE_MEMORY
|
||||
|
@ -435,10 +506,10 @@ inline void memcopy4(void *dest,void *source) {
|
|||
#endif
|
||||
|
||||
/** \brief number of analog input signals. Normally 1 for each temperature sensor */
|
||||
#define ANALOG_INPUTS (EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS+THERMO_ANALOG_INPUTS)
|
||||
#define ANALOG_INPUTS (EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS+THERMO_ANALOG_INPUTS+KEYPAD_ANALOG_INPUTS)
|
||||
#if ANALOG_INPUTS > 0
|
||||
/** Channels are the MUX-part of ADMUX register */
|
||||
#define ANALOG_INPUT_CHANNELS {EXT0_ANALOG_CHANNEL EXT1_ANALOG_CHANNEL EXT2_ANALOG_CHANNEL EXT3_ANALOG_CHANNEL EXT4_ANALOG_CHANNEL EXT5_ANALOG_CHANNEL BED_ANALOG_CHANNEL THERMO_ANALOG_CHANNEL}
|
||||
#define ANALOG_INPUT_CHANNELS {EXT0_ANALOG_CHANNEL EXT1_ANALOG_CHANNEL EXT2_ANALOG_CHANNEL EXT3_ANALOG_CHANNEL EXT4_ANALOG_CHANNEL EXT5_ANALOG_CHANNEL BED_ANALOG_CHANNEL THERMO_ANALOG_CHANNEL KEYPAD_ANALOG_CHANNEL}
|
||||
#endif
|
||||
|
||||
#define MENU_MODE_SD_MOUNTED 1
|
||||
|
@ -762,9 +833,9 @@ public:
|
|||
extern const uint8 osAnalogInputChannels[] PROGMEM;
|
||||
//extern uint8 osAnalogInputCounter[ANALOG_INPUTS];
|
||||
//extern uint osAnalogInputBuildup[ANALOG_INPUTS];
|
||||
//extern uint8 osAnalogInputPos; // Current sampling position
|
||||
#if ANALOG_INPUTS > 0
|
||||
extern volatile uint osAnalogInputValues[ANALOG_INPUTS];
|
||||
//extern uint8 osAnalogInputPos; // Current sampling position
|
||||
#if ANALOG_INPUTS > 0
|
||||
extern volatile uint osAnalogInputValues[ANALOG_INPUTS];
|
||||
#endif
|
||||
#define PWM_HEATED_BED NUM_EXTRUDER
|
||||
#define PWM_BOARD_FAN PWM_HEATED_BED+1
|
||||
|
@ -844,9 +915,9 @@ public:
|
|||
//SdVolume volume;
|
||||
//SdFile root;
|
||||
//SdFile dir[SD_MAX_FOLDER_DEPTH+1];
|
||||
SdFile file;
|
||||
#if JSON_OUTPUT
|
||||
GCodeFileInfo fileInfo;
|
||||
SdFile file;
|
||||
#if JSON_OUTPUT
|
||||
GCodeFileInfo fileInfo;
|
||||
#endif
|
||||
uint32_t filesize;
|
||||
uint32_t sdpos;
|
||||
|
@ -876,11 +947,11 @@ public:
|
|||
file.seekSet(sdpos);
|
||||
}
|
||||
void printStatus();
|
||||
void ls();
|
||||
#if JSON_OUTPUT
|
||||
void lsJSON(const char *filename);
|
||||
void JSONFileInfo(const char *filename);
|
||||
static void printEscapeChars(const char *s);
|
||||
void ls();
|
||||
#if JSON_OUTPUT
|
||||
void lsJSON(const char *filename);
|
||||
void JSONFileInfo(const char *filename);
|
||||
static void printEscapeChars(const char *s);
|
||||
#endif
|
||||
void startWrite(char *filename);
|
||||
void deleteFile(char *filename);
|
||||
|
|
|
@ -110,19 +110,19 @@ Custom M Codes
|
|||
- M207 X<XY jerk> Z<Z Jerk> E<ExtruderJerk> - Changes current jerk values, but do not store them in eeprom.
|
||||
- M209 S<0/1> - Enable/disable autoretraction
|
||||
- M220 S<Feedrate multiplier in percent> - Increase/decrease given feedrate
|
||||
- M221 S<Extrusion flow multiplier in percent> - Increase/decrease given flow rate
|
||||
- M228 P<pin> S<state 0/1> - Wait for pin getting state S. Add X0 to init as input without pullup and X1 for input with pullup.
|
||||
- M221 S<Extrusion flow multiplier in percent> - Increase/decrease given flow rate
|
||||
- M226 P<pin> S<state 0/1> - Wait for pin getting state S. Add X0 to init as input without pullup and X1 for input with pullup.
|
||||
- M231 S<OPS_MODE> X<Min_Distance> Y<Retract> Z<Backlash> F<ReatrctMove> - Set OPS parameter
|
||||
- M232 - Read and reset max. advance values
|
||||
- M233 X<AdvanceK> Y<AdvanceL> - Set temporary advance K-value to X and linear term advanceL to Y
|
||||
- M251 Measure Z steps from homing stop (Delta printers). S0 - Reset, S1 - Print, S2 - Store to Z length (also EEPROM if enabled)
|
||||
- M280 S<mode> - Set ditto printing mode. mode: 0 = off, 1 = 1 extra extruder, 2 = 2 extra extruder, 3 = 3 extra extruders
|
||||
- M281 Test if watchdog is running and working.
|
||||
- M281 Test if watchdog is running and working. Use M281 X0 to disable watchdog on AVR boards. Sometimes needed for boards with old bootloaders to allow reflashing.
|
||||
- M300 S<Frequency> P<DurationMillis> play frequency
|
||||
- M302 S<0 or 1> - allow cold extrusion. Without S parameter it will allow. S1 will disallow.
|
||||
- M303 P<extruder/bed> S<printTemerature> X0 R<Repetitions>- Autodetect pid values. Use P<NUM_EXTRUDER> for heated bed. X0 saves result in EEPROM. R is number of cycles.
|
||||
- M320 - Activate autolevel
|
||||
- M321 - Deactivate autolevel
|
||||
- M320 S<0/1> - Activate autolevel, S1 stores it in eeprom
|
||||
- M321 S<0/1> - Deactivate autolevel, S1 stores it in eeprom
|
||||
- M322 - Reset autolevel matrix
|
||||
- M323 S0/S1 enable disable distortion correction P0 = not permanent, P1 = permanent = default
|
||||
- M340 P<servoId> S<pulseInUS> R<autoOffIn ms>: servoID = 0..3, Servos are controlled by a pulse with normally between 500 and 2500 with 1500ms in center position. 0 turns servo off. R allows automatic disabling after a while.
|
||||
|
@ -131,10 +131,10 @@ Custom M Codes
|
|||
- M360 - show configuration
|
||||
- M400 - Wait until move buffers empty.
|
||||
- M401 - Store x, y and z position.
|
||||
- M402 - Go to stored position. If X, Y or Z is specified, only these coordinates are used. F changes feedrate fo rthat move.
|
||||
- M450 - Reports printer mode
|
||||
- M451 - Set printer mode to FFF
|
||||
- M452 - Set printer mode to laser
|
||||
- M402 - Go to stored position. If X, Y or Z is specified, only these coordinates are used. F changes feedrate fo rthat move.
|
||||
- M450 - Reports printer mode
|
||||
- M451 - Set printer mode to FFF
|
||||
- M452 - Set printer mode to laser
|
||||
- M453 - Set printer mode to CNC
|
||||
- M460 X<minTemp> Y<maxTemp> : Set temperature range for thermistor controlled fan
|
||||
- M500 Store settings to EEPROM
|
||||
|
@ -145,6 +145,7 @@ Custom M Codes
|
|||
- M601 S<1/0> - Pause extruders. Paused extrudes disable heaters and motor. Unpausing reheats extruder to old temp.
|
||||
- M602 S<1/0> P<1/0>- Debug jam control (S) Disable jam control (P). If enabled it will log signal changes and will not trigger jam errors!
|
||||
- M908 P<address> S<value> : Set stepper current for digipot (RAMBO board)
|
||||
- M999 - Continue from fatal error. M999 S1 will create a fatal error for testing.
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
|
|
|
@ -78,7 +78,11 @@ void SDCard::initsd()
|
|||
if(READ(SDCARDDETECT) != SDCARDDETECTINVERTED)
|
||||
return;
|
||||
#endif
|
||||
HAL::pingWatchdog();
|
||||
HAL::delayMilliseconds(50); // wait for stabilization of contacts, bootup ...
|
||||
fat.begin(SDSS, SPI_FULL_SPEED); // dummy init of SD_CARD
|
||||
HAL::delayMilliseconds(50); // wait for init end
|
||||
HAL::pingWatchdog();
|
||||
/*if(dir[0].isOpen())
|
||||
dir[0].close();*/
|
||||
if(!fat.begin(SDSS, SPI_FULL_SPEED))
|
||||
|
@ -89,6 +93,7 @@ void SDCard::initsd()
|
|||
}
|
||||
sdactive = true;
|
||||
Printer::setMenuMode(MENU_MODE_SD_MOUNTED, true);
|
||||
HAL::pingWatchdog();
|
||||
|
||||
fat.chdir();
|
||||
if(selectFile("init.g", true))
|
||||
|
@ -173,7 +178,7 @@ void SDCard::stopPrint()
|
|||
GCode::executeFString(PSTR(SD_RUN_ON_STOP));
|
||||
if(SD_STOP_HEATER_AND_MOTORS_ON_STOP) {
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
Printer::kill(true);
|
||||
Printer::kill(false);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -426,93 +431,93 @@ void SDCard::ls()
|
|||
file.ls(0, 0);
|
||||
Com::printFLN(Com::tEndFileList);
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
void SDCard::lsJSON(const char *filename)
|
||||
{
|
||||
SdBaseFile dir;
|
||||
fat.chdir();
|
||||
if (*filename == 0) {
|
||||
dir.openRoot(fat.vol());
|
||||
} else {
|
||||
if (!dir.open(fat.vwd(), filename, O_READ) || !dir.isDir()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tFileOpenFailed);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
Com::printF(Com::tJSONDir);
|
||||
SDCard::printEscapeChars(filename);
|
||||
Com::printF(Com::tJSONFiles);
|
||||
dir.lsJSON();
|
||||
Com::printFLN(Com::tJSONArrayEnd);
|
||||
}
|
||||
|
||||
void SDCard::printEscapeChars(const char *s) {
|
||||
for (unsigned int i = 0; i < strlen(s); ++i) {
|
||||
switch (s[i]) {
|
||||
case '"':
|
||||
case '/':
|
||||
case '\b':
|
||||
case '\f':
|
||||
case '\n':
|
||||
case '\r':
|
||||
case '\t':
|
||||
case '\\':
|
||||
Com::print('\\');
|
||||
break;
|
||||
}
|
||||
Com::print(s[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::JSONFileInfo(const char* filename) {
|
||||
SdBaseFile targetFile;
|
||||
GCodeFileInfo *info,tmpInfo;
|
||||
if (strlen(filename) == 0) {
|
||||
targetFile = file;
|
||||
info = &fileInfo;
|
||||
} else {
|
||||
if (!targetFile.open(fat.vwd(), filename, O_READ) || targetFile.isDir()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tFileOpenFailed);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
info = &tmpInfo;
|
||||
info->init(targetFile);
|
||||
}
|
||||
if (!targetFile.isOpen()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tNotSDPrinting);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
|
||||
// {"err":0,"size":457574,"height":4.00,"layerHeight":0.25,"filament":[6556.3],"generatedBy":"Slic3r 1.1.7 on 2014-11-09 at 17:11:32"}
|
||||
Com::printF(Com::tJSONFileInfoStart);
|
||||
Com::print(info->fileSize);
|
||||
Com::printF(Com::tJSONFileInfoHeight);
|
||||
Com::print(info->objectHeight);
|
||||
Com::printF(Com::tJSONFileInfoLayerHeight);
|
||||
Com::print(info->layerHeight);
|
||||
Com::printF(Com::tJSONFileInfoFilament);
|
||||
Com::print(info->filamentNeeded);
|
||||
Com::printF(Com::tJSONFileInfoGeneratedBy);
|
||||
Com::print(info->generatedBy);
|
||||
Com::print('"');
|
||||
if (strlen(filename) == 0) {
|
||||
Com::printF(Com::tJSONFileInfoName);
|
||||
file.printName();
|
||||
Com::print('"');
|
||||
}
|
||||
Com::print('}');
|
||||
Com::println();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#if JSON_OUTPUT
|
||||
void SDCard::lsJSON(const char *filename)
|
||||
{
|
||||
SdBaseFile dir;
|
||||
fat.chdir();
|
||||
if (*filename == 0) {
|
||||
dir.openRoot(fat.vol());
|
||||
} else {
|
||||
if (!dir.open(fat.vwd(), filename, O_READ) || !dir.isDir()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tFileOpenFailed);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
Com::printF(Com::tJSONDir);
|
||||
SDCard::printEscapeChars(filename);
|
||||
Com::printF(Com::tJSONFiles);
|
||||
dir.lsJSON();
|
||||
Com::printFLN(Com::tJSONArrayEnd);
|
||||
}
|
||||
|
||||
void SDCard::printEscapeChars(const char *s) {
|
||||
for (unsigned int i = 0; i < strlen(s); ++i) {
|
||||
switch (s[i]) {
|
||||
case '"':
|
||||
case '/':
|
||||
case '\b':
|
||||
case '\f':
|
||||
case '\n':
|
||||
case '\r':
|
||||
case '\t':
|
||||
case '\\':
|
||||
Com::print('\\');
|
||||
break;
|
||||
}
|
||||
Com::print(s[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::JSONFileInfo(const char* filename) {
|
||||
SdBaseFile targetFile;
|
||||
GCodeFileInfo *info,tmpInfo;
|
||||
if (strlen(filename) == 0) {
|
||||
targetFile = file;
|
||||
info = &fileInfo;
|
||||
} else {
|
||||
if (!targetFile.open(fat.vwd(), filename, O_READ) || targetFile.isDir()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tFileOpenFailed);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
info = &tmpInfo;
|
||||
info->init(targetFile);
|
||||
}
|
||||
if (!targetFile.isOpen()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tNotSDPrinting);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
|
||||
// {"err":0,"size":457574,"height":4.00,"layerHeight":0.25,"filament":[6556.3],"generatedBy":"Slic3r 1.1.7 on 2014-11-09 at 17:11:32"}
|
||||
Com::printF(Com::tJSONFileInfoStart);
|
||||
Com::print(info->fileSize);
|
||||
Com::printF(Com::tJSONFileInfoHeight);
|
||||
Com::print(info->objectHeight);
|
||||
Com::printF(Com::tJSONFileInfoLayerHeight);
|
||||
Com::print(info->layerHeight);
|
||||
Com::printF(Com::tJSONFileInfoFilament);
|
||||
Com::print(info->filamentNeeded);
|
||||
Com::printF(Com::tJSONFileInfoGeneratedBy);
|
||||
Com::print(info->generatedBy);
|
||||
Com::print('"');
|
||||
if (strlen(filename) == 0) {
|
||||
Com::printF(Com::tJSONFileInfoName);
|
||||
file.printName();
|
||||
Com::print('"');
|
||||
}
|
||||
Com::print('}');
|
||||
Com::println();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
bool SDCard::selectFile(const char *filename, bool silent)
|
||||
{
|
||||
|
@ -536,9 +541,9 @@ bool SDCard::selectFile(const char *filename, bool silent)
|
|||
{
|
||||
Com::printF(Com::tFileOpened, oldP);
|
||||
Com::printFLN(Com::tSpaceSizeColon,file.fileSize());
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
fileInfo.init(file);
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
fileInfo.init(file);
|
||||
#endif
|
||||
sdpos = 0;
|
||||
filesize = file.fileSize();
|
||||
|
|
|
@ -652,7 +652,7 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil
|
|||
dir_t *p = NULL;
|
||||
//uint8_t cnt=0;
|
||||
//char *oldpathend = pathend;
|
||||
bool firstFile = true;
|
||||
bool firstFile = true;
|
||||
|
||||
parent->rewind();
|
||||
|
||||
|
@ -661,29 +661,29 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil
|
|||
HAL::pingWatchdog();
|
||||
if (! (DIR_IS_FILE(p) || DIR_IS_SUBDIR(p))) continue;
|
||||
if (strcmp(tempLongFilename, "..") == 0) continue;
|
||||
if (tempLongFilename[0] == '.') continue; // MAC CRAP
|
||||
if (DIR_IS_SUBDIR(p)) {
|
||||
if (level >= SD_MAX_FOLDER_DEPTH) continue; // can't go deeper
|
||||
if (level < SD_MAX_FOLDER_DEPTH && findFilename == NULL) {
|
||||
if (level && !isJson) {
|
||||
Com::print(fullName);
|
||||
Com::printF(Com::tSlash);
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
if (isJson) {
|
||||
if (!firstFile) Com::print(',');
|
||||
Com::print('"');Com::print('*');
|
||||
SDCard::printEscapeChars(tempLongFilename);
|
||||
Com::print('"');
|
||||
firstFile = false;
|
||||
} else {
|
||||
Com::print(tempLongFilename);
|
||||
Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories.
|
||||
}
|
||||
#else
|
||||
Com::print(tempLongFilename);
|
||||
Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories.
|
||||
#endif
|
||||
if (tempLongFilename[0] == '.') continue; // MAC CRAP
|
||||
if (DIR_IS_SUBDIR(p)) {
|
||||
if (level >= SD_MAX_FOLDER_DEPTH) continue; // can't go deeper
|
||||
if (level < SD_MAX_FOLDER_DEPTH && findFilename == NULL) {
|
||||
if (level && !isJson) {
|
||||
Com::print(fullName);
|
||||
Com::printF(Com::tSlash);
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
if (isJson) {
|
||||
if (!firstFile) Com::print(',');
|
||||
Com::print('"');Com::print('*');
|
||||
SDCard::printEscapeChars(tempLongFilename);
|
||||
Com::print('"');
|
||||
firstFile = false;
|
||||
} else {
|
||||
Com::print(tempLongFilename);
|
||||
Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories.
|
||||
}
|
||||
#else
|
||||
Com::print(tempLongFilename);
|
||||
Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories.
|
||||
#endif
|
||||
}
|
||||
SdBaseFile next;
|
||||
char *tmp;
|
||||
|
@ -729,22 +729,22 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil
|
|||
{
|
||||
Com::print(fullName);
|
||||
Com::printF(Com::tSlash);
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
if (isJson) {
|
||||
if (!firstFile) Com::printF(Com::tComma);
|
||||
Com::print('"');
|
||||
SDCard::printEscapeChars(tempLongFilename);
|
||||
Com::print('"');
|
||||
firstFile = false;
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
Com::print(tempLongFilename);
|
||||
#if SD_EXTENDED_DIR
|
||||
Com::printF(Com::tSpace, (long) p->fileSize);
|
||||
#endif
|
||||
Com::println();
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
if (isJson) {
|
||||
if (!firstFile) Com::printF(Com::tComma);
|
||||
Com::print('"');
|
||||
SDCard::printEscapeChars(tempLongFilename);
|
||||
Com::print('"');
|
||||
firstFile = false;
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
Com::print(tempLongFilename);
|
||||
#if SD_EXTENDED_DIR
|
||||
Com::printF(Com::tSpace, (long) p->fileSize);
|
||||
#endif
|
||||
Com::println();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -768,24 +768,24 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil
|
|||
* \param[in] indent Amount of space before file name. Used for recursive
|
||||
* list to indicate subdirectory level.
|
||||
*/
|
||||
void SdBaseFile::ls(uint8_t flags, uint8_t indent) {
|
||||
SdBaseFile parent;
|
||||
rewind();
|
||||
*fullName = 0;
|
||||
pathend = fullName;
|
||||
parent = *this;
|
||||
lsRecursive(&parent, 0, NULL, NULL, false);
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
void SdBaseFile::lsJSON() {
|
||||
SdBaseFile parent;
|
||||
rewind();
|
||||
*fullName = 0;
|
||||
parent = *this;
|
||||
lsRecursive(&parent, 0, NULL, NULL, true);
|
||||
}
|
||||
#endif
|
||||
void SdBaseFile::ls(uint8_t flags, uint8_t indent) {
|
||||
SdBaseFile parent;
|
||||
rewind();
|
||||
*fullName = 0;
|
||||
pathend = fullName;
|
||||
parent = *this;
|
||||
lsRecursive(&parent, 0, NULL, NULL, false);
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
void SdBaseFile::lsJSON() {
|
||||
SdBaseFile parent;
|
||||
rewind();
|
||||
*fullName = 0;
|
||||
parent = *this;
|
||||
lsRecursive(&parent, 0, NULL, NULL, true);
|
||||
}
|
||||
#endif
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
// saves 32 bytes on stack for ls recursion
|
||||
|
|
|
@ -43,6 +43,7 @@ int8_t GCode::waitingForResend = -1; ///< Waiting for line to be resend. -1 =
|
|||
volatile uint8_t GCode::bufferLength = 0; ///< Number of commands stored in gcode_buffer
|
||||
millis_t GCode::timeOfLastDataPacket = 0; ///< Time, when we got the last data packet. Used to detect missing uint8_ts.
|
||||
uint8_t GCode::formatErrors = 0;
|
||||
PGM_P GCode::fatalErrorMsg = NULL; ///< message unset = no fatal error
|
||||
|
||||
/** \page Repetier-protocol
|
||||
|
||||
|
@ -183,11 +184,11 @@ void GCode::checkAndPushCommand()
|
|||
}
|
||||
#ifdef DEBUG_COM_ERRORS
|
||||
if(M == 666) // force an communication error
|
||||
{
|
||||
{
|
||||
lastLineNumber++;
|
||||
return;
|
||||
} else if(M == 668) {
|
||||
lastLineNumber = 0; // simulate a reset so lines are out of resend buffer
|
||||
} else if(M == 668) {
|
||||
lastLineNumber = 0; // simulate a reset so lines are out of resend buffer
|
||||
}
|
||||
#endif // DEBUG_COM_ERRORS
|
||||
}
|
||||
|
@ -221,11 +222,22 @@ void GCode::checkAndPushCommand()
|
|||
return;
|
||||
}
|
||||
lastLineNumber = actLineNumber;
|
||||
}
|
||||
pushCommand();
|
||||
} else if(lastLineNumber && !(hasM() && M == 117)) { // once line number always line number!
|
||||
if(Printer::debugErrors())
|
||||
{
|
||||
Com::printErrorFLN(PSTR("Missing linenumber"));
|
||||
}
|
||||
requestResend();
|
||||
return;
|
||||
}
|
||||
if(GCode::hasFatalError() && !(hasM() && M==999)) {
|
||||
GCode::reportFatalError();
|
||||
} else {
|
||||
pushCommand();
|
||||
}
|
||||
#ifdef DEBUG_COM_ERRORS
|
||||
if(hasM() && M == 667)
|
||||
return; // omit ok
|
||||
if(hasM() && M == 667)
|
||||
return; // omit ok
|
||||
#endif
|
||||
#if ACK_WITH_LINENUMBER
|
||||
Com::printFLN(Com::tOkSpace, actLineNumber);
|
||||
|
@ -342,7 +354,7 @@ void GCode::readFromSerial()
|
|||
if(!HAL::serialByteAvailable())
|
||||
{
|
||||
if((waitingForResend >= 0 || commandsReceivingWritePosition > 0) && time - timeOfLastDataPacket > 200)
|
||||
{
|
||||
{
|
||||
// Com::printF(PSTR("WFR:"),waitingForResend);Com::printF(PSTR(" CRWP:"),commandsReceivingWritePosition);commandReceiving[commandsReceivingWritePosition] = 0;Com::printFLN(PSTR(" GOT:"),(char*)commandReceiving);
|
||||
requestResend(); // Something is wrong, a started line was not continued in the last second
|
||||
timeOfLastDataPacket = time;
|
||||
|
@ -417,7 +429,7 @@ void GCode::readFromSerial()
|
|||
}
|
||||
else
|
||||
{
|
||||
if(ch == ';') commentDetected = true; // ignore new data until lineend
|
||||
if(ch == ';') commentDetected = true; // ignore new data until line end
|
||||
if(commentDetected) commandsReceivingWritePosition--;
|
||||
}
|
||||
}
|
||||
|
@ -500,7 +512,7 @@ void GCode::readFromSerial()
|
|||
}
|
||||
else
|
||||
{
|
||||
if(ch == ';') commentDetected = true; // ignore new data until lineend
|
||||
if(ch == ';') commentDetected = true; // ignore new data until line end
|
||||
if(commentDetected) commandsReceivingWritePosition--;
|
||||
}
|
||||
}
|
||||
|
@ -705,7 +717,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
internalCommand = !fromSerial;
|
||||
char c;
|
||||
while ( (c = *(pos++)) )
|
||||
{
|
||||
{
|
||||
if(c == '(' || c == '%') break; // alternative comment or program block
|
||||
switch(c)
|
||||
{
|
||||
|
@ -846,7 +858,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 8;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'C':
|
||||
case 'c':
|
||||
{
|
||||
|
@ -854,7 +866,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 16;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'H':
|
||||
case 'h':
|
||||
{
|
||||
|
@ -862,7 +874,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 32;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'A':
|
||||
case 'a':
|
||||
{
|
||||
|
@ -870,7 +882,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 64;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'B':
|
||||
case 'b':
|
||||
{
|
||||
|
@ -878,7 +890,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 128;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'K':
|
||||
case 'k':
|
||||
{
|
||||
|
@ -886,7 +898,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 256;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'L':
|
||||
case 'l':
|
||||
{
|
||||
|
@ -894,7 +906,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 512;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case 'O':
|
||||
case 'o':
|
||||
{
|
||||
|
@ -902,7 +914,7 @@ bool GCode::parseAscii(char *line,bool fromSerial)
|
|||
params2 |= 1024;
|
||||
params |= 4096; // Needs V2 for saving
|
||||
break;
|
||||
}
|
||||
}
|
||||
case '*' : //checksum
|
||||
{
|
||||
uint8_t checksum_given = parseLongValue(pos);
|
||||
|
@ -1009,193 +1021,223 @@ void GCode::printCommand()
|
|||
}
|
||||
Com::println();
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
|
||||
// --------------------------------------------------------------- //
|
||||
// Code that gets gcode information is adapted from RepRapFirmware //
|
||||
// Originally licenced under GPL //
|
||||
// Authors: reprappro, dc42, dcnewman, others //
|
||||
// Source: https://github.com/dcnewman/RepRapFirmware //
|
||||
// Copy date: 15 Nov 2015 //
|
||||
// --------------------------------------------------------------- //
|
||||
|
||||
void GCodeFileInfo::init(SdBaseFile &file) {
|
||||
this->fileSize = file.fileSize();
|
||||
this->filamentNeeded = 0.0;
|
||||
this->objectHeight = 0.0;
|
||||
this->layerHeight = 0.0;
|
||||
if (!file.isOpen()) return;
|
||||
bool genByFound = false, layerHeightFound = false, filamentNeedFound = false;
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
#define GCI_BUF_SIZE 120
|
||||
#else
|
||||
#define GCI_BUF_SIZE 1024
|
||||
#endif
|
||||
// READ 4KB FROM THE BEGINNING
|
||||
char buf[GCI_BUF_SIZE];
|
||||
for (int i = 0; i < 4096; i += GCI_BUF_SIZE-50) {
|
||||
if(!file.seekSet(i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true;
|
||||
if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true;
|
||||
if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true;
|
||||
if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight;
|
||||
}
|
||||
|
||||
// READ 4KB FROM END
|
||||
for (int i = 0; i < 4096; i += GCI_BUF_SIZE-50) {
|
||||
if(!file.seekEnd(-4096 + i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true;
|
||||
if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true;
|
||||
if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true;
|
||||
if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight;
|
||||
}
|
||||
|
||||
get_objectHeight:
|
||||
// MOVE FROM END UP IN 1KB BLOCKS UP TO 30KB
|
||||
for (int i = GCI_BUF_SIZE; i < 30000; i += GCI_BUF_SIZE-50) {
|
||||
if(!file.seekEnd(-i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (findTotalHeight(buf, this->objectHeight)) break;
|
||||
}
|
||||
file.seekSet(0);
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findGeneratedBy(char *buf, char *genBy) {
|
||||
// Slic3r & S3D
|
||||
const char* generatedByString = PSTR("generated by ");
|
||||
char* pos = strstr_P(buf, generatedByString);
|
||||
if (pos) {
|
||||
pos += strlen_P(generatedByString);
|
||||
size_t i = 0;
|
||||
while (i < GENBY_SIZE - 1 && *pos >= ' ') {
|
||||
char c = *pos++;
|
||||
if (c == '"' || c == '\\') {
|
||||
// Need to escape the quote-mark for JSON
|
||||
if (i > GENBY_SIZE - 3) break;
|
||||
genBy[i++] = '\\';
|
||||
}
|
||||
genBy[i++] = c;
|
||||
}
|
||||
genBy[i] = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
// CURA
|
||||
const char* slicedAtString = PSTR(";Sliced at: ");
|
||||
pos = strstr_P(buf, slicedAtString);
|
||||
if (pos) {
|
||||
strcpy_P(genBy, PSTR("Cura"));
|
||||
return true;
|
||||
}
|
||||
|
||||
// UNKNOWN
|
||||
strcpy_P(genBy, PSTR("Unknown"));
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findLayerHeight(char *buf, float &layerHeight) {
|
||||
// SLIC3R
|
||||
layerHeight = 0;
|
||||
const char* layerHeightSlic3r = PSTR("; layer_height ");
|
||||
char *pos = strstr_P(buf, layerHeightSlic3r);
|
||||
if (pos) {
|
||||
pos += strlen_P(layerHeightSlic3r);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
// CURA
|
||||
const char* layerHeightCura = PSTR("Layer height: ");
|
||||
pos = strstr_P(buf, layerHeightCura);
|
||||
if (pos) {
|
||||
pos += strlen_P(layerHeightCura);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findFilamentNeed(char *buf, float &filament) {
|
||||
const char* filamentUsedStr = PSTR("filament used");
|
||||
const char* pos = strstr_P(buf, filamentUsedStr);
|
||||
filament = 0;
|
||||
if (pos != NULL) {
|
||||
pos += strlen_P(filamentUsedStr);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos; // this allows for " = " from default slic3r comment and ": " from default Cura comment
|
||||
}
|
||||
if (isDigit(*pos)) {
|
||||
char *q;
|
||||
filament += strtod(pos, &q);
|
||||
if (*q == 'm' && *(q + 1) != 'm') {
|
||||
filament *= 1000.0; // Cura outputs filament used in metres not mm
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findTotalHeight(char *buf, float &height) {
|
||||
int len = 1024;
|
||||
bool inComment, inRelativeMode = false;
|
||||
unsigned int zPos;
|
||||
for (int i = len - 5; i > 0; i--) {
|
||||
if (inRelativeMode) {
|
||||
inRelativeMode = !(buf[i] == 'G' && buf[i + 1] == '9' && buf[i + 2] == '1' && buf[i + 3] <= ' ');
|
||||
} else if (buf[i] == 'G') {
|
||||
// Ignore G0/G1 codes if absolute mode was switched back using G90 (typical for Cura files)
|
||||
if (buf[i + 1] == '9' && buf[i + 2] == '0' && buf[i + 3] <= ' ') {
|
||||
inRelativeMode = true;
|
||||
} else if ((buf[i + 1] == '0' || buf[i + 1] == '1') && buf[i + 2] == ' ') {
|
||||
// Look for last "G0/G1 ... Z#HEIGHT#" command as generated by common slicers
|
||||
// Looks like we found a controlled move, however it could be in a comment, especially when using slic3r 1.1.1
|
||||
inComment = false;
|
||||
size_t j = i;
|
||||
while (j != 0) {
|
||||
--j;
|
||||
char c = buf[j];
|
||||
if (c == '\n' || c == '\r') break;
|
||||
if (c == ';') {
|
||||
// It is in a comment, so give up on this one
|
||||
inComment = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (inComment) continue;
|
||||
|
||||
// Find 'Z' position and grab that value
|
||||
zPos = 0;
|
||||
for (int j = i + 3; j < len - 2; j++) {
|
||||
char c = buf[j];
|
||||
if (c < ' ') {
|
||||
// Skip all whitespaces...
|
||||
while (j < len - 2 && c <= ' ') {
|
||||
c = buf[++j];
|
||||
}
|
||||
// ...to make sure ";End" doesn't follow G0 .. Z#HEIGHT#
|
||||
if (zPos != 0) {
|
||||
//debugPrintf("Found at offset %u text: %.100s\n", zPos, &buf[zPos + 1]);
|
||||
height = strtod(&buf[zPos + 1], NULL);
|
||||
return true;
|
||||
}
|
||||
break;
|
||||
} else if (c == ';') break;
|
||||
else if (c == 'Z') zPos = j;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif // JSON_OUTPUT
|
||||
|
||||
void GCode::fatalError(FSTRINGPARAM(message)) {
|
||||
fatalErrorMsg = message;
|
||||
#if SDSUPPORT
|
||||
if(sd.sdmode != 0) { // stop sd print to prevent damage
|
||||
sd.stopPrint();
|
||||
}
|
||||
#endif
|
||||
if(Printer::currentPosition[Z_AXIS] < Printer::zMin + Printer::zLength - 15)
|
||||
PrintLine::moveRelativeDistanceInStepsReal(0,0,10*Printer::axisStepsPerMM[Z_AXIS],0,Printer::homingFeedrate[Z_AXIS],true,true);
|
||||
EVENT_FATAL_ERROR_OCCURED
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
Printer::kill(true);
|
||||
reportFatalError();
|
||||
}
|
||||
|
||||
void GCode::reportFatalError() {
|
||||
Com::printF(Com::tFatal);
|
||||
Com::printF(fatalErrorMsg);
|
||||
Com::printFLN(PSTR(" Printer stopped and heaters disabled due to this error. Fix error and restart with M999."));
|
||||
UI_ERROR_P(fatalErrorMsg)
|
||||
}
|
||||
|
||||
void GCode::resetFatalError() {
|
||||
TemperatureController::resetAllErrorStates();
|
||||
fatalErrorMsg = NULL;
|
||||
UI_ERROR("");
|
||||
EVENT_CONTINUE_FROM_FATAL_ERROR
|
||||
Com::printFLN(PSTR("info:Continue from fatal state"));
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
|
||||
// --------------------------------------------------------------- //
|
||||
// Code that gets gcode information is adapted from RepRapFirmware //
|
||||
// Originally licensed under GPL //
|
||||
// Authors: reprappro, dc42, dcnewman, others //
|
||||
// Source: https://github.com/dcnewman/RepRapFirmware //
|
||||
// Copy date: 15 Nov 2015 //
|
||||
// --------------------------------------------------------------- //
|
||||
|
||||
void GCodeFileInfo::init(SdBaseFile &file) {
|
||||
this->fileSize = file.fileSize();
|
||||
this->filamentNeeded = 0.0;
|
||||
this->objectHeight = 0.0;
|
||||
this->layerHeight = 0.0;
|
||||
if (!file.isOpen()) return;
|
||||
bool genByFound = false, layerHeightFound = false, filamentNeedFound = false;
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
#define GCI_BUF_SIZE 120
|
||||
#else
|
||||
#define GCI_BUF_SIZE 1024
|
||||
#endif
|
||||
// READ 4KB FROM THE BEGINNING
|
||||
char buf[GCI_BUF_SIZE];
|
||||
for (int i = 0; i < 4096; i += GCI_BUF_SIZE-50) {
|
||||
if(!file.seekSet(i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true;
|
||||
if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true;
|
||||
if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true;
|
||||
if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight;
|
||||
}
|
||||
|
||||
// READ 4KB FROM END
|
||||
for (int i = 0; i < 4096; i += GCI_BUF_SIZE-50) {
|
||||
if(!file.seekEnd(-4096 + i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true;
|
||||
if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true;
|
||||
if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true;
|
||||
if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight;
|
||||
}
|
||||
|
||||
get_objectHeight:
|
||||
// MOVE FROM END UP IN 1KB BLOCKS UP TO 30KB
|
||||
for (int i = GCI_BUF_SIZE; i < 30000; i += GCI_BUF_SIZE-50) {
|
||||
if(!file.seekEnd(-i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (findTotalHeight(buf, this->objectHeight)) break;
|
||||
}
|
||||
file.seekSet(0);
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findGeneratedBy(char *buf, char *genBy) {
|
||||
// Slic3r & S3D
|
||||
const char* generatedByString = PSTR("generated by ");
|
||||
char* pos = strstr_P(buf, generatedByString);
|
||||
if (pos) {
|
||||
pos += strlen_P(generatedByString);
|
||||
size_t i = 0;
|
||||
while (i < GENBY_SIZE - 1 && *pos >= ' ') {
|
||||
char c = *pos++;
|
||||
if (c == '"' || c == '\\') {
|
||||
// Need to escape the quote-mark for JSON
|
||||
if (i > GENBY_SIZE - 3) break;
|
||||
genBy[i++] = '\\';
|
||||
}
|
||||
genBy[i++] = c;
|
||||
}
|
||||
genBy[i] = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
// CURA
|
||||
const char* slicedAtString = PSTR(";Sliced at: ");
|
||||
pos = strstr_P(buf, slicedAtString);
|
||||
if (pos) {
|
||||
strcpy_P(genBy, PSTR("Cura"));
|
||||
return true;
|
||||
}
|
||||
|
||||
// UNKNOWN
|
||||
strcpy_P(genBy, PSTR("Unknown"));
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findLayerHeight(char *buf, float &layerHeight) {
|
||||
// SLIC3R
|
||||
layerHeight = 0;
|
||||
const char* layerHeightSlic3r = PSTR("; layer_height ");
|
||||
char *pos = strstr_P(buf, layerHeightSlic3r);
|
||||
if (pos) {
|
||||
pos += strlen_P(layerHeightSlic3r);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
// CURA
|
||||
const char* layerHeightCura = PSTR("Layer height: ");
|
||||
pos = strstr_P(buf, layerHeightCura);
|
||||
if (pos) {
|
||||
pos += strlen_P(layerHeightCura);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findFilamentNeed(char *buf, float &filament) {
|
||||
const char* filamentUsedStr = PSTR("filament used");
|
||||
const char* pos = strstr_P(buf, filamentUsedStr);
|
||||
filament = 0;
|
||||
if (pos != NULL) {
|
||||
pos += strlen_P(filamentUsedStr);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos; // this allows for " = " from default slic3r comment and ": " from default Cura comment
|
||||
}
|
||||
if (isDigit(*pos)) {
|
||||
char *q;
|
||||
filament += strtod(pos, &q);
|
||||
if (*q == 'm' && *(q + 1) != 'm') {
|
||||
filament *= 1000.0; // Cura outputs filament used in metres not mm
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findTotalHeight(char *buf, float &height) {
|
||||
int len = 1024;
|
||||
bool inComment, inRelativeMode = false;
|
||||
unsigned int zPos;
|
||||
for (int i = len - 5; i > 0; i--) {
|
||||
if (inRelativeMode) {
|
||||
inRelativeMode = !(buf[i] == 'G' && buf[i + 1] == '9' && buf[i + 2] == '1' && buf[i + 3] <= ' ');
|
||||
} else if (buf[i] == 'G') {
|
||||
// Ignore G0/G1 codes if absolute mode was switched back using G90 (typical for Cura files)
|
||||
if (buf[i + 1] == '9' && buf[i + 2] == '0' && buf[i + 3] <= ' ') {
|
||||
inRelativeMode = true;
|
||||
} else if ((buf[i + 1] == '0' || buf[i + 1] == '1') && buf[i + 2] == ' ') {
|
||||
// Look for last "G0/G1 ... Z#HEIGHT#" command as generated by common slicers
|
||||
// Looks like we found a controlled move, however it could be in a comment, especially when using slic3r 1.1.1
|
||||
inComment = false;
|
||||
size_t j = i;
|
||||
while (j != 0) {
|
||||
--j;
|
||||
char c = buf[j];
|
||||
if (c == '\n' || c == '\r') break;
|
||||
if (c == ';') {
|
||||
// It is in a comment, so give up on this one
|
||||
inComment = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (inComment) continue;
|
||||
|
||||
// Find 'Z' position and grab that value
|
||||
zPos = 0;
|
||||
for (int j = i + 3; j < len - 2; j++) {
|
||||
char c = buf[j];
|
||||
if (c < ' ') {
|
||||
// Skip all whitespaces...
|
||||
while (j < len - 2 && c <= ' ') {
|
||||
c = buf[++j];
|
||||
}
|
||||
// ...to make sure ";End" doesn't follow G0 .. Z#HEIGHT#
|
||||
if (zPos != 0) {
|
||||
//debugPrintf("Found at offset %u text: %.100s\n", zPos, &buf[zPos + 1]);
|
||||
height = strtod(&buf[zPos + 1], NULL);
|
||||
return true;
|
||||
}
|
||||
break;
|
||||
} else if (c == ';') break;
|
||||
else if (c == 'Z') zPos = j;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif // JSON_OUTPUT
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#ifndef _GCODE_H
|
||||
#define _GCODE_H
|
||||
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define ARRAY_SIZE(_x) (sizeof(_x)/sizeof(_x[0]))
|
||||
class SDCard;
|
||||
class GCode // 52 uint8_ts per command needed
|
||||
|
@ -182,7 +182,12 @@ public:
|
|||
static void pushCommand();
|
||||
static void executeFString(FSTRINGPARAM(cmd));
|
||||
static uint8_t computeBinarySize(char *ptr);
|
||||
|
||||
static void fatalError(FSTRINGPARAM(message));
|
||||
static void reportFatalError();
|
||||
static void resetFatalError();
|
||||
inline static bool hasFatalError() {
|
||||
return fatalErrorMsg != NULL;
|
||||
}
|
||||
friend class SDCard;
|
||||
friend class UIDisplay;
|
||||
private:
|
||||
|
@ -199,13 +204,14 @@ private:
|
|||
}
|
||||
inline long parseLongValue(char *s)
|
||||
{
|
||||
char *endPtr;
|
||||
char *endPtr;
|
||||
while(*s == 32) s++; // skip spaces
|
||||
long l = (strtol(s, &endPtr, 10));
|
||||
if(s == endPtr) l=0; // treat empty string argument "p " as "p0"
|
||||
return l;
|
||||
}
|
||||
|
||||
static FSTRINGPARAM(fatalErrorMsg);
|
||||
static GCode commandsBuffered[GCODE_BUFFER_SIZE]; ///< Buffer for received commands.
|
||||
static uint8_t bufferReadIndex; ///< Read position in gcode_buffer.
|
||||
static uint8_t bufferWriteIndex; ///< Write position in gcode_buffer.
|
||||
|
@ -224,26 +230,26 @@ private:
|
|||
static uint8_t formatErrors; ///< Number of sequential format errors
|
||||
};
|
||||
|
||||
#if JSON_OUTPUT
|
||||
#include "SdFat.h"
|
||||
// Struct to hold Gcode file information 32 bytes
|
||||
#define GENBY_SIZE 16
|
||||
class GCodeFileInfo {
|
||||
public:
|
||||
void init(SdBaseFile &file);
|
||||
|
||||
unsigned long fileSize;
|
||||
float objectHeight;
|
||||
float layerHeight;
|
||||
float filamentNeeded;
|
||||
char generatedBy[GENBY_SIZE];
|
||||
|
||||
bool findGeneratedBy(char *buf, char *genBy);
|
||||
bool findLayerHeight(char *buf, float &layerHeight);
|
||||
bool findFilamentNeed(char *buf, float &filament);
|
||||
bool findTotalHeight(char *buf, float &objectHeight);
|
||||
};
|
||||
#endif
|
||||
#if JSON_OUTPUT
|
||||
#include "SdFat.h"
|
||||
// Struct to hold Gcode file information 32 bytes
|
||||
#define GENBY_SIZE 16
|
||||
class GCodeFileInfo {
|
||||
public:
|
||||
void init(SdBaseFile &file);
|
||||
|
||||
unsigned long fileSize;
|
||||
float objectHeight;
|
||||
float layerHeight;
|
||||
float filamentNeeded;
|
||||
char generatedBy[GENBY_SIZE];
|
||||
|
||||
bool findGeneratedBy(char *buf, char *genBy);
|
||||
bool findLayerHeight(char *buf, float &layerHeight);
|
||||
bool findFilamentNeed(char *buf, float &filament);
|
||||
bool findTotalHeight(char *buf, float &objectHeight);
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
// File generated by LCD Assistant
|
||||
// http://en.radzio.dxp.pl/bitmap_converter/
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
|
||||
#ifndef CUSTOM_LOGO
|
||||
#define LOGO_WIDTH 60
|
||||
#define LOGO_HEIGHT 64
|
||||
|
@ -41,6 +41,6 @@ const unsigned char logo[] PROGMEM = { //AVR-GCC, WinAVR
|
|||
0x00, 0x00, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0D, 0xF8, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
};
|
||||
#else
|
||||
LOGO_BITMAP
|
||||
#endif
|
||||
#else
|
||||
LOGO_BITMAP
|
||||
#endif
|
||||
|
|
5641
Repetier/motion.cpp
5641
Repetier/motion.cpp
File diff suppressed because it is too large
Load diff
1434
Repetier/motion.h
1434
Repetier/motion.h
File diff suppressed because it is too large
Load diff
199
Repetier/pins.h
199
Repetier/pins.h
|
@ -365,12 +365,9 @@ STEPPER_CURRENT_CONTROL
|
|||
#if MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 35
|
||||
#define KNOWN_BOARD 1
|
||||
|
||||
//////////////////FIX THIS//////////////
|
||||
#ifndef __AVR_ATmega1280__
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#if !(defined (__AVR_ATmega1280__ ) || defined (__AVR_ATmega2560__ ))
|
||||
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// uncomment one of the following lines for RAMPS v1.3 or v1.0, comment both for v1.2 or 1.1
|
||||
// #define RAMPS_V_1_3
|
||||
|
@ -972,7 +969,7 @@ STEPPER_CURRENT_CONTROL
|
|||
#define HEATER_2_PIN -1
|
||||
// bed (change to 12 for breakout pin on header)
|
||||
#define HEATER_1_PIN 10
|
||||
|
||||
|
||||
#define ORIG_X_ENABLE_PIN 14
|
||||
#define ORIG_Y_ENABLE_PIN 14
|
||||
#define ORIG_Z_ENABLE_PIN 26
|
||||
|
@ -997,86 +994,86 @@ STEPPER_CURRENT_CONTROL
|
|||
#endif
|
||||
|
||||
#if MOTHERBOARD == 66
|
||||
#define KNOWN_BOARD 1
|
||||
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
// X/Y/Z Steppers and MIN endstops verified
|
||||
|
||||
#define ORIG_X_STEP_PIN 54
|
||||
#define ORIG_X_DIR_PIN 55
|
||||
#define ORIG_X_ENABLE_PIN 38
|
||||
#define ORIG_X_MIN_PIN 3
|
||||
#define ORIG_X_MAX_PIN -1
|
||||
|
||||
#define ORIG_Y_STEP_PIN 60
|
||||
#define ORIG_Y_DIR_PIN 61
|
||||
#define ORIG_Y_ENABLE_PIN 56
|
||||
#define ORIG_Y_MIN_PIN 14
|
||||
#define ORIG_Y_MAX_PIN -1
|
||||
|
||||
#define ORIG_Z_STEP_PIN 46
|
||||
#define ORIG_Z_DIR_PIN 48
|
||||
#define ORIG_Z_ENABLE_PIN 63
|
||||
#define ORIG_Z_MIN_PIN 18
|
||||
#define ORIG_Z_MAX_PIN -1
|
||||
|
||||
#define ORIG_E0_STEP_PIN 26
|
||||
#define ORIG_E0_DIR_PIN 28
|
||||
#define ORIG_E0_ENABLE_PIN 24
|
||||
|
||||
#define ORIG_E1_STEP_PIN -1
|
||||
#define ORIG_E1_DIR_PIN -1
|
||||
#define ORIG_E1_ENABLE_PIN -1
|
||||
|
||||
#define SDPOWER -1
|
||||
#define SDSS 25
|
||||
#define ORIG_SDCARDDETECT -1
|
||||
|
||||
#define LED_PIN 13
|
||||
#define ORIG_FAN_PIN 8
|
||||
#define ORIG_PS_ON_PIN -1
|
||||
|
||||
// schematic: HEATER1 (Extruder)
|
||||
#define HEATER_0_PIN 10
|
||||
// schematic: HEATER2 (Heated Bed)
|
||||
#define HEATER_1_PIN 9
|
||||
#define HEATER_2_PIN -1
|
||||
|
||||
// ANALOG NUMBERING
|
||||
// schematic: THERM1 (Extruder)
|
||||
#define TEMP_0_PIN 13
|
||||
// schematic: THERM2 (Heated Bed)
|
||||
#define TEMP_1_PIN 14
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN,
|
||||
#define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN,
|
||||
|
||||
// following pins (LCD, ENCODER, SDCARD) reverse engineered from schematic diagram:
|
||||
|
||||
#ifdef ULTRA_LCD
|
||||
#ifdef NEWPANEL
|
||||
|
||||
#define LCD_PINS_RS 27
|
||||
#define LCD_PINS_ENABLE 29
|
||||
#define LCD_PINS_D4 37
|
||||
#define LCD_PINS_D5 35
|
||||
#define LCD_PINS_D6 33
|
||||
#define LCD_PINS_D7 31
|
||||
|
||||
#define BTN_EN1 16
|
||||
#define BTN_EN2 17
|
||||
#define BTN_ENC 23
|
||||
|
||||
#endif
|
||||
#endif //ULTRA_LCD
|
||||
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#define KNOWN_BOARD 1
|
||||
|
||||
#ifndef __AVR_ATmega2560__
|
||||
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
|
||||
#endif
|
||||
|
||||
// X/Y/Z Steppers and MIN endstops verified
|
||||
|
||||
#define ORIG_X_STEP_PIN 54
|
||||
#define ORIG_X_DIR_PIN 55
|
||||
#define ORIG_X_ENABLE_PIN 38
|
||||
#define ORIG_X_MIN_PIN 3
|
||||
#define ORIG_X_MAX_PIN -1
|
||||
|
||||
#define ORIG_Y_STEP_PIN 60
|
||||
#define ORIG_Y_DIR_PIN 61
|
||||
#define ORIG_Y_ENABLE_PIN 56
|
||||
#define ORIG_Y_MIN_PIN 14
|
||||
#define ORIG_Y_MAX_PIN -1
|
||||
|
||||
#define ORIG_Z_STEP_PIN 46
|
||||
#define ORIG_Z_DIR_PIN 48
|
||||
#define ORIG_Z_ENABLE_PIN 63
|
||||
#define ORIG_Z_MIN_PIN 18
|
||||
#define ORIG_Z_MAX_PIN -1
|
||||
|
||||
#define ORIG_E0_STEP_PIN 26
|
||||
#define ORIG_E0_DIR_PIN 28
|
||||
#define ORIG_E0_ENABLE_PIN 24
|
||||
|
||||
#define ORIG_E1_STEP_PIN -1
|
||||
#define ORIG_E1_DIR_PIN -1
|
||||
#define ORIG_E1_ENABLE_PIN -1
|
||||
|
||||
#define SDPOWER -1
|
||||
#define SDSS 25
|
||||
#define ORIG_SDCARDDETECT -1
|
||||
|
||||
#define LED_PIN 13
|
||||
#define ORIG_FAN_PIN 8
|
||||
#define ORIG_PS_ON_PIN -1
|
||||
|
||||
// schematic: HEATER1 (Extruder)
|
||||
#define HEATER_0_PIN 10
|
||||
// schematic: HEATER2 (Heated Bed)
|
||||
#define HEATER_1_PIN 9
|
||||
#define HEATER_2_PIN -1
|
||||
|
||||
// ANALOG NUMBERING
|
||||
// schematic: THERM1 (Extruder)
|
||||
#define TEMP_0_PIN 13
|
||||
// schematic: THERM2 (Heated Bed)
|
||||
#define TEMP_1_PIN 14
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN,
|
||||
#define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN,
|
||||
|
||||
// following pins (LCD, ENCODER, SDCARD) reverse engineered from schematic diagram:
|
||||
|
||||
#ifdef ULTRA_LCD
|
||||
#ifdef NEWPANEL
|
||||
|
||||
#define LCD_PINS_RS 27
|
||||
#define LCD_PINS_ENABLE 29
|
||||
#define LCD_PINS_D4 37
|
||||
#define LCD_PINS_D5 35
|
||||
#define LCD_PINS_D6 33
|
||||
#define LCD_PINS_D7 31
|
||||
|
||||
#define BTN_EN1 16
|
||||
#define BTN_EN2 17
|
||||
#define BTN_ENC 23
|
||||
|
||||
#endif
|
||||
#endif //ULTRA_LCD
|
||||
|
||||
#define SCK_PIN 52
|
||||
#define MISO_PIN 50
|
||||
#define MOSI_PIN 51
|
||||
#define MAX6675_SS 53
|
||||
#endif
|
||||
|
||||
|
@ -1911,13 +1908,13 @@ STEPPER_CURRENT_CONTROL
|
|||
#define SDSUPPORT 1 // already defined in config.h
|
||||
#define SDCARDDETECTINVERTED 1 // already defined in config.h
|
||||
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
// PINB.1, 20, SCK
|
||||
#define SCK_PIN 52
|
||||
#define SCK_PIN 52
|
||||
// PINB.3, 22, MISO
|
||||
#define MISO_PIN 50
|
||||
#define MISO_PIN 50
|
||||
// PINB.2, 21, MOSI
|
||||
#define MOSI_PIN 51
|
||||
#define MOSI_PIN 51
|
||||
//53 // PINB.0, 19, SS
|
||||
#define MAX6675_SS -1
|
||||
|
||||
|
@ -2000,7 +1997,7 @@ STEPPER_CURRENT_CONTROL
|
|||
// Thermocouple 1
|
||||
#define TEMP_4_PIN 4
|
||||
#define THERMOCOUPLE_0_PIN 8
|
||||
#define THERMOCOUPLE_0_PIN 4
|
||||
#define THERMOCOUPLE_1_PIN 4
|
||||
|
||||
// Beeper on AUX-4
|
||||
#define BEEPER_PIN 64
|
||||
|
@ -2200,10 +2197,14 @@ S2(ext)=8
|
|||
S3(ext)=9
|
||||
*/
|
||||
|
||||
#define TEMP_0_PIN 15 // Extruder 1
|
||||
#define TEMP_2_PIN 14 // Extruder 2
|
||||
#define TEMP_3_PIN 13 // Extruder 3
|
||||
#define TEMP_1_PIN 12 // Heated bed
|
||||
// Extruder 1 - Thermistor 1
|
||||
#define TEMP_0_PIN 15
|
||||
// Extruder 2 - Thermistor 2
|
||||
#define TEMP_2_PIN 14
|
||||
// Extruder 3 - Thermistor 3
|
||||
#define TEMP_3_PIN 13
|
||||
// Heated bed - Thermistor 4
|
||||
#define TEMP_1_PIN 12
|
||||
|
||||
#define THERMOCOUPLE_0_PIN 11
|
||||
#define THERMOCOUPLE_1_PIN 10
|
||||
|
@ -2353,7 +2354,7 @@ S3(ext)=9
|
|||
#if MOTHERBOARD == 314
|
||||
#define KNOWN_BOARD 1
|
||||
#define PiBot true
|
||||
|
||||
|
||||
#if PiBot_V_1_4==true || PiBot_V_1_6==true || PiBot_V_2_0==true
|
||||
#define PiBot_V_1_0 false
|
||||
#else
|
||||
|
@ -2777,10 +2778,10 @@ S3(ext)=9
|
|||
#ifndef FAN_BOARD_PIN
|
||||
#define FAN_BOARD_PIN -1
|
||||
#endif
|
||||
|
||||
#ifndef E2_PINS
|
||||
#define E2_PINS
|
||||
#endif
|
||||
|
||||
#ifndef E2_PINS
|
||||
#define E2_PINS
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER==1
|
||||
#undef E1_PINS
|
||||
|
|
7044
Repetier/u8glib_ex.h
7044
Repetier/u8glib_ex.h
File diff suppressed because it is too large
Load diff
144
Repetier/ui.cpp
144
Repetier/ui.cpp
|
@ -144,11 +144,11 @@ char displayCache[UI_ROWS][MAX_COLS+1];
|
|||
// .***. 14
|
||||
// *.*.* 21
|
||||
// ..*.. 4
|
||||
// ..*.. 4
|
||||
// ..*.. 4
|
||||
// ***.. 28
|
||||
// ..... 0
|
||||
// ..... 0
|
||||
// ..... 0
|
||||
const uint8_t character_back[8] PROGMEM = {4,14,21,4,28,0,0,0};
|
||||
const uint8_t character_back[8] PROGMEM = {4, 14, 21, 4, 4, 4, 28, 0};
|
||||
// Degrees sign - code 2
|
||||
// ..*.. 4
|
||||
// .*.*. 10
|
||||
|
@ -781,6 +781,9 @@ void initializeLCD()
|
|||
#ifdef U8GLIB_SSD1306_SW_SPI
|
||||
u8g_InitSPI(&u8g,&u8g_dev_ssd1306_128x64_sw_spi, UI_DISPLAY_D4_PIN, UI_DISPLAY_ENABLE_PIN, UI_DISPLAY_RS_PIN, U8G_PIN_NONE, U8G_PIN_NONE);
|
||||
#endif
|
||||
#ifdef U8GLIB_SH1106_SW_SPI
|
||||
u8g_InitSPI(&u8g,&u8g_dev_sh1106_128x64_sw_spi, UI_DISPLAY_D4_PIN, UI_DISPLAY_ENABLE_PIN, UI_DISPLAY_RS_PIN, U8G_PIN_NONE, U8G_PIN_NONE);
|
||||
#endif
|
||||
#ifdef U8GLIB_KS0108_FAST
|
||||
u8g_Init8Bit(&u8g,&u8g_dev_ks0108_128x64_fast,UI_DISPLAY_D0_PIN,UI_DISPLAY_D1_PIN,UI_DISPLAY_D2_PIN,UI_DISPLAY_D3_PIN,UI_DISPLAY_D4_PIN,UI_DISPLAY_D5_PIN,UI_DISPLAY_D6_PIN,UI_DISPLAY_D7_PIN,UI_DISPLAY_ENABLE_PIN,UI_DISPLAY_CS1,UI_DISPLAY_CS2,
|
||||
UI_DISPLAY_DI,UI_DISPLAY_RW_PIN,UI_DISPLAY_RESET_PIN);
|
||||
|
@ -920,8 +923,8 @@ void UIDisplay::initialize()
|
|||
do
|
||||
{
|
||||
u8g_DrawBitmapP(&u8g, 128 - LOGO_WIDTH, 0, ((LOGO_WIDTH + 7) / 8), LOGO_HEIGHT, logo);
|
||||
for(uint8_t y = 0; y < UI_ROWS; y++) displayCache[y][0] = 0;
|
||||
#ifdef CUSTOM_LOGO
|
||||
for(uint8_t y = 0; y < UI_ROWS; y++) displayCache[y][0] = 0;
|
||||
#ifdef CUSTOM_LOGO
|
||||
printRowP(4, PSTR("Repetier"));
|
||||
printRowP(5, PSTR("Ver " REPETIER_VERSION));
|
||||
#else
|
||||
|
@ -929,7 +932,7 @@ void UIDisplay::initialize()
|
|||
printRowP(1, PSTR("Ver " REPETIER_VERSION));
|
||||
printRowP(3, PSTR("Machine:"));
|
||||
printRowP(4, PSTR(UI_PRINTER_NAME));
|
||||
printRowP(5, PSTR(UI_PRINTER_COMPANY));
|
||||
printRowP(5, PSTR(UI_PRINTER_COMPANY));
|
||||
#endif
|
||||
}
|
||||
while( u8g_NextPage(&u8g) ); //end picture loop
|
||||
|
@ -1258,26 +1261,33 @@ void UIDisplay::parse(const char *txt,bool ram)
|
|||
break;
|
||||
}
|
||||
break;
|
||||
case 'd':
|
||||
if(c2 == 'o') addStringOnOff(Printer::debugEcho());
|
||||
else if(c2 == 'i') addStringOnOff(Printer::debugInfo());
|
||||
else if(c2 == 'e') addStringOnOff(Printer::debugErrors());
|
||||
else if(c2 == 'd') addStringOnOff(Printer::debugDryrun());
|
||||
break;
|
||||
case 'D':
|
||||
case 'd': // debug boolean
|
||||
if (c2 == 'o') addStringOnOff(Printer::debugEcho());
|
||||
if (c2 == 'i') addStringOnOff(Printer::debugInfo());
|
||||
if (c2 == 'e') addStringOnOff(Printer::debugErrors());
|
||||
if (c2 == 'd') addStringOnOff(Printer::debugDryrun());
|
||||
if (c2 == 'p') addStringOnOff(Printer::debugEndStop());
|
||||
if (c2 == 'x') addStringP(Endstops::xMin() ? ui_selected : ui_unselected);
|
||||
if (c2 == 'X') addStringP(Endstops::xMax() ? ui_selected : ui_unselected);
|
||||
if (c2 == 'y') addStringP(Endstops::yMin() ? ui_selected : ui_unselected);
|
||||
if (c2 == 'Y') addStringP(Endstops::yMax() ? ui_selected : ui_unselected);
|
||||
if (c2 == 'z') addStringP(Endstops::zMin() ? ui_selected : ui_unselected);
|
||||
if (c2 == 'Z') addStringP(Endstops::zMax() ? ui_selected : ui_unselected);
|
||||
break;
|
||||
case 'D':
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
if(c2>='0' && c2<='9')
|
||||
{
|
||||
addStringP(Extruder::dittoMode==c2-'0'?ui_selected:ui_unselected);
|
||||
}
|
||||
#endif
|
||||
addStringP(Extruder::dittoMode==c2-'0' ? ui_selected : ui_unselected);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case 'e': // Extruder temperature
|
||||
{
|
||||
if(c2 == 'I')
|
||||
{
|
||||
//give integer display
|
||||
//char c2 = (ram ? *(txt++) : pgm_read_byte(txt++));
|
||||
//char c2 = (ram ? *(txt++) : pgm_read_byte(txt++));
|
||||
txt++; // just skip c sign
|
||||
ivalue = 0;
|
||||
}
|
||||
|
@ -1287,17 +1297,17 @@ void UIDisplay::parse(const char *txt,bool ram)
|
|||
{
|
||||
addStringP(Printer::relativeExtruderCoordinateMode ? Com::translatedF(UI_TEXT_YES_ID) : Com::translatedF(UI_TEXT_NO_ID));
|
||||
break;
|
||||
}
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
if(c2 == 'd') { // ditto copy mode
|
||||
addInt(Extruder::dittoMode,1,' ');
|
||||
break;
|
||||
}
|
||||
}
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
if(c2 == 'd') { // ditto copy mode
|
||||
addInt(Extruder::dittoMode,1,' ');
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#if NUM_TEMPERATURE_LOOPS > 0
|
||||
uint8_t eid = NUM_EXTRUDER; // default = BED if c2 not specified extruder number
|
||||
if(c2 == 'c') eid = Extruder::current->id;
|
||||
else if(c2 >= '0' && c2 <= '9') eid = c2 - '0';
|
||||
#if NUM_TEMPERATURE_LOOPS > 0
|
||||
if(Printer::isAnyTempsensorDefect())
|
||||
{
|
||||
if(eid == 0 && ++beepdelay > 30) beepdelay = 0; // beep every 30 seconds
|
||||
|
@ -1321,7 +1331,7 @@ void UIDisplay::parse(const char *txt,bool ram)
|
|||
addStringP(PSTR(" jam "));
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
if(c2 == 'c') fvalue = Extruder::current->tempControl.currentTemperatureC;
|
||||
else if(c2 >= '0' && c2 <= '9') fvalue=extruder[c2 - '0'].tempControl.currentTemperatureC;
|
||||
|
@ -1492,18 +1502,18 @@ void UIDisplay::parse(const char *txt,bool ram)
|
|||
if(c2 >= 'x' && c2 <= 'z') addFloat(Printer::axisStepsPerMM[c2 - 'x'], 3, 1);
|
||||
if(c2 == 'e') addFloat(Extruder::current->stepsPerMM, 3, 1);
|
||||
break;
|
||||
case 'T': // Print offsets
|
||||
if(c2=='2')
|
||||
addFloat(-Printer::coordinateOffset[Z_AXIS],2,2);
|
||||
else
|
||||
addFloat(-Printer::coordinateOffset[c2-'0'],4,0);
|
||||
case 'T': // Print offsets
|
||||
if(c2=='2')
|
||||
addFloat(-Printer::coordinateOffset[Z_AXIS],2,2);
|
||||
else
|
||||
addFloat(-Printer::coordinateOffset[c2-'0'],4,0);
|
||||
break;
|
||||
case 'U':
|
||||
if(c2 == 't') // Printing time
|
||||
{
|
||||
#if EEPROM_MODE
|
||||
bool alloff = true;
|
||||
#if NUM_TEMPERATURE_LOOPS > 0
|
||||
#if NUM_TEMPERATURE_LOOPS > 0
|
||||
for(uint8_t i = 0; i < NUM_EXTRUDER; i++)
|
||||
if(tempController[i]->targetTemperatureC > 15) alloff = false;
|
||||
#endif
|
||||
|
@ -1646,17 +1656,17 @@ void UIDisplay::parse(const char *txt,bool ram)
|
|||
break;
|
||||
case 'y':
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
if(c2 >= '0' && c2 <= '3') fvalue = (float)Printer::currentDeltaPositionSteps[c2 - '0']*Printer::invAxisStepsPerMM[c2-'0'];
|
||||
if(c2 >= '0' && c2 <= '3') fvalue = (float)Printer::currentNonlinearPositionSteps[c2 - '0']*Printer::invAxisStepsPerMM[c2-'0'];
|
||||
addFloat(fvalue,3,2);
|
||||
#endif
|
||||
break;
|
||||
case 'z':
|
||||
#if EEPROM_MODE != 0 && FEATURE_Z_PROBE
|
||||
if(c2 == 'h') { // write z probe height
|
||||
addFloat(EEPROM::zProbeHeight(),3,2);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case 'z':
|
||||
#if EEPROM_MODE != 0 && FEATURE_Z_PROBE
|
||||
if(c2 == 'h') { // write z probe height
|
||||
addFloat(EEPROM::zProbeHeight(),3,2);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
if(c2=='2')
|
||||
addFloat(-Printer::coordinateOffset[Z_AXIS],2,2);
|
||||
else
|
||||
|
@ -1667,8 +1677,8 @@ void UIDisplay::parse(const char *txt,bool ram)
|
|||
uid.printCols[col] = 0;
|
||||
}
|
||||
void UIDisplay::showLanguageSelectionWizard() {
|
||||
#if EEPROM_MODE != 0
|
||||
pushMenu(&ui_menu_languages_wiz,true);
|
||||
#if EEPROM_MODE != 0
|
||||
pushMenu(&ui_menu_languages_wiz,true);
|
||||
#endif
|
||||
}
|
||||
void UIDisplay::setStatusP(PGM_P txt,bool error)
|
||||
|
@ -1824,6 +1834,7 @@ void sdrefresh(uint16_t &r,char cache[UI_ROWS][MAX_COLS+1])
|
|||
// Refresh current menu page
|
||||
void UIDisplay::refreshPage()
|
||||
{
|
||||
Endstops::update();
|
||||
#if UI_DISPLAY_TYPE == DISPLAY_GAMEDUINO2
|
||||
GD2::refresh();
|
||||
#else
|
||||
|
@ -1831,14 +1842,14 @@ void UIDisplay::refreshPage()
|
|||
uint8_t mtype = UI_MENU_TYPE_INFO;
|
||||
char cache[UI_ROWS][MAX_COLS + 1];
|
||||
adjustMenuPos();
|
||||
#if UI_AUTORETURN_TO_MENU_AFTER!=0
|
||||
#if UI_AUTORETURN_TO_MENU_AFTER != 0
|
||||
// Reset timeout on menu back when user active on menu
|
||||
if (uid.encoderLast != encoderStartScreen)
|
||||
ui_autoreturn_time = HAL::timeInMilliseconds() + UI_AUTORETURN_TO_MENU_AFTER;
|
||||
#endif
|
||||
encoderStartScreen = uid.encoderLast;
|
||||
|
||||
// Copy result into cache
|
||||
Endstops::update();
|
||||
if(menuLevel == 0) // Top level menu
|
||||
{
|
||||
UIMenu *men = (UIMenu*)pgm_read_word(&(ui_pages[menuPos[0]]));
|
||||
|
@ -2005,11 +2016,11 @@ void UIDisplay::refreshPage()
|
|||
#endif
|
||||
if(menuLevel == 0 && menuPos[0] == 0 ) // Main menu with special graphics
|
||||
{
|
||||
//ext1 and ext2 animation symbols
|
||||
//ext1 and ext2 animation symbols
|
||||
#if NUM_EXTRUDER < 3
|
||||
if(extruder[0].tempControl.targetTemperatureC > 30)
|
||||
#else
|
||||
if(Extruder::current->tempControl.targetTemperatureC > 30)
|
||||
if(extruder[0].tempControl.targetTemperatureC > 30)
|
||||
#else
|
||||
if(Extruder::current->tempControl.targetTemperatureC > 30)
|
||||
#endif
|
||||
cache[0][0] = Printer::isAnimation()?'\x08':'\x09';
|
||||
else
|
||||
|
@ -2018,21 +2029,21 @@ void UIDisplay::refreshPage()
|
|||
if(extruder[1].tempControl.targetTemperatureC > 30)
|
||||
cache[1][0] = Printer::isAnimation()?'\x08':'\x09';
|
||||
else
|
||||
cache[1][0] = '\x0a'; //off
|
||||
cache[1][0] = '\x0a'; //off
|
||||
#endif
|
||||
#if HAVE_HEATED_BED
|
||||
//heatbed animated icons
|
||||
//heated bed animated icons
|
||||
uint8_t lin = 2 - ((NUM_EXTRUDER != 2) ? 1 : 0);
|
||||
if(heatedBedController.targetTemperatureC > 30)
|
||||
cache[lin][0] = Printer::isAnimation() ? '\x0c' : '\x0d';
|
||||
else
|
||||
cache[lin][0] = '\x0b';
|
||||
#endif
|
||||
#if FAN_PIN>-1 && FEATURE_FAN_CONTROL
|
||||
#if FAN_PIN > -1 && FEATURE_FAN_CONTROL
|
||||
//fan
|
||||
fanPercent = Printer::getFanSpeed() * 100 / 255;
|
||||
fanString[1] = 0;
|
||||
if(fanPercent > 0) //fan running anmation
|
||||
if(fanPercent > 0) //fan running animation
|
||||
{
|
||||
fanString[0] = Printer::isAnimation() ? '\x0e' : '\x0f';
|
||||
}
|
||||
|
@ -2081,11 +2092,11 @@ void UIDisplay::refreshPage()
|
|||
if(u8g_IsBBXIntersection(&u8g, 0, 30 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT))
|
||||
printU8GRow(117,30,fanString);
|
||||
drawVProgressBar(116, 0, 9, 20, fanPercent);
|
||||
if(u8g_IsBBXIntersection(&u8g, 0, 42 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT))
|
||||
printU8GRow(0,42,cache[3]); //mul + extruded
|
||||
if(u8g_IsBBXIntersection(&u8g, 0, 52 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT))
|
||||
printU8GRow(0,52,cache[4]); //buf
|
||||
#endif
|
||||
if(u8g_IsBBXIntersection(&u8g, 0, 42 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT))
|
||||
printU8GRow(0,42,cache[3]); //multiplier + extruded
|
||||
if(u8g_IsBBXIntersection(&u8g, 0, 52 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT))
|
||||
printU8GRow(0,52,cache[4]); //buffer usage
|
||||
#if SDSUPPORT
|
||||
//SD Card
|
||||
if(sd.sdactive && u8g_IsBBXIntersection(&u8g, 66, 52 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT))
|
||||
|
@ -2865,7 +2876,7 @@ ZPOS2:
|
|||
if(rate == 0) p -= 2;
|
||||
p += increment;
|
||||
if(p < 0) p = 0;
|
||||
if(p > static_cast<int16_t>(sizeof(baudrates)/4) - 2)
|
||||
if(p > static_cast<int16_t>(sizeof(baudrates)/4) - 2)
|
||||
p = sizeof(baudrates)/4 - 2;
|
||||
baudrate = pgm_read_dword(&(baudrates[p]));
|
||||
}
|
||||
|
@ -3064,6 +3075,9 @@ int UIDisplay::executeAction(unsigned int action, bool allowMoves)
|
|||
case UI_ACTION_DEBUG_ERROR:
|
||||
Printer::toggleErrors();
|
||||
break;
|
||||
case UI_ACTION_DEBUG_ENDSTOP:
|
||||
Printer::toggleEndStop();
|
||||
break;
|
||||
case UI_ACTION_DEBUG_DRYRUN:
|
||||
Printer::toggleDryRun();
|
||||
if(Printer::debugDryrun()) // simulate movements without printing
|
||||
|
@ -3119,7 +3133,7 @@ int UIDisplay::executeAction(unsigned int action, bool allowMoves)
|
|||
#endif
|
||||
break;
|
||||
case UI_ACTION_COOLDOWN:
|
||||
UI_STATUS_F(Com::translatedF(UI_TEXT_COOLDOWN_ID));
|
||||
UI_STATUS_F(Com::translatedF(UI_TEXT_COOLDOWN_ID));
|
||||
for(int i = 0;i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(0, i);
|
||||
#if HAVE_HEATED_BED
|
||||
|
@ -3179,14 +3193,14 @@ int UIDisplay::executeAction(unsigned int action, bool allowMoves)
|
|||
currHeaterForSetup = &(Extruder::current->tempControl);
|
||||
Printer::setMenuMode(MENU_MODE_FULL_PID, currHeaterForSetup->heatManager == 1);
|
||||
Printer::setMenuMode(MENU_MODE_DEADTIME, currHeaterForSetup->heatManager == 3);
|
||||
break;
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
break;
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
case UI_DITTO_0:
|
||||
case UI_DITTO_1:
|
||||
case UI_DITTO_2:
|
||||
case UI_DITTO_3:
|
||||
Extruder::dittoMode = action - UI_DITTO_0;
|
||||
break;
|
||||
case UI_DITTO_3:
|
||||
Extruder::dittoMode = action - UI_DITTO_0;
|
||||
break;
|
||||
#endif
|
||||
#if EEPROM_MODE != 0
|
||||
case UI_ACTION_STORE_EEPROM:
|
||||
|
@ -3460,7 +3474,7 @@ int UIDisplay::executeAction(unsigned int action, bool allowMoves)
|
|||
Printer::currentPositionSteps[Z_AXIS] = 0;
|
||||
Printer::updateDerivedParameter();
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentDeltaPositionSteps);
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentNonlinearPositionSteps);
|
||||
#endif
|
||||
Printer::updateCurrentPosition(true);
|
||||
Com::printFLN(Com::tZProbePrinterHeight, Printer::zLength);
|
||||
|
@ -3587,6 +3601,8 @@ int UIDisplay::executeAction(unsigned int action, bool allowMoves)
|
|||
case UI_ACTION_LANGUAGE_FR:
|
||||
case UI_ACTION_LANGUAGE_CZ:
|
||||
case UI_ACTION_LANGUAGE_PL:
|
||||
case UI_ACTION_LANGUAGE_TR:
|
||||
case UI_ACTION_LANGUAGE_FI:
|
||||
Com::selectLanguage(action - UI_ACTION_LANGUAGE_EN);
|
||||
#if EEPROM_MODE != 0
|
||||
EEPROM::storeDataIntoEEPROM(0); // remember for next start
|
||||
|
|
687
Repetier/ui.h
687
Repetier/ui.h
File diff suppressed because it is too large
Load diff
|
@ -101,30 +101,32 @@ What display type do you use?
|
|||
#define UI_DISPLAY_TYPE 5
|
||||
|
||||
#if UI_DISPLAY_TYPE == DISPLAY_U8G // Special case for graphic displays
|
||||
|
||||
// You need to define which controller you use and set pins accodringly
|
||||
|
||||
// For software spi assign these definitions
|
||||
|
||||
// You need to define which controller you use and set pins accodringly
|
||||
|
||||
// For software spi assign these definitions
|
||||
// SCK Pin: UI_DISPLAY_D4_PIN
|
||||
// Mosi Pin: UI_DISPLAY_ENABLE_PIN
|
||||
// CD Pin: UI_DISPLAY_RS_PIN
|
||||
|
||||
// ST7920 with software SPI
|
||||
#define U8GLIB_ST7920
|
||||
// SSD1306 with software SPI
|
||||
//#define U8GLIB_SSD1306_SW_SPI
|
||||
// SSD1306 over I2C using hardware I2C pins
|
||||
//#define U8GLIB_SSD1306_I2C
|
||||
// For the 8 bit ks0108 display you need to set these pins
|
||||
// UI_DISPLAY_D0_PIN,UI_DISPLAY_D1_PIN,UI_DISPLAY_D2_PIN,UI_DISPLAY_D3_PIN,UI_DISPLAY_D4_PIN,UI_DISPLAY_D5_PIN,UI_DISPLAY_D6_PIN,UI_DISPLAY_D7_PIN
|
||||
// UI_DISPLAY_ENABLE_PIN,UI_DISPLAY_CS1,UI_DISPLAY_CS2,
|
||||
// UI_DISPLAY_DI,UI_DISPLAY_RW_PIN,UI_DISPLAY_RESET_PIN
|
||||
|
||||
// ST7920 with software SPI
|
||||
#define U8GLIB_ST7920
|
||||
// SSD1306 with software SPI
|
||||
//#define U8GLIB_SSD1306_SW_SPI
|
||||
// SH1106 with software SPI
|
||||
// U8GLIB_SH1106_SW_SPI
|
||||
// SSD1306 over I2C using hardware I2C pins
|
||||
//#define U8GLIB_SSD1306_I2C
|
||||
// For the 8 bit ks0108 display you need to set these pins
|
||||
// UI_DISPLAY_D0_PIN,UI_DISPLAY_D1_PIN,UI_DISPLAY_D2_PIN,UI_DISPLAY_D3_PIN,UI_DISPLAY_D4_PIN,UI_DISPLAY_D5_PIN,UI_DISPLAY_D6_PIN,UI_DISPLAY_D7_PIN
|
||||
// UI_DISPLAY_ENABLE_PIN,UI_DISPLAY_CS1,UI_DISPLAY_CS2,
|
||||
// UI_DISPLAY_DI,UI_DISPLAY_RW_PIN,UI_DISPLAY_RESET_PIN
|
||||
//#define U8GLIB_KS0108
|
||||
//#define U8GLIB_KS0108_FAST
|
||||
// UI_DISPLAY_RS_PIN = CS
|
||||
//#define U8GLIB_KS0108_FAST
|
||||
// UI_DISPLAY_RS_PIN = CS
|
||||
// UI_DISPLAY_D5_PIN = A0
|
||||
//#define U8GLIB_ST7565_NHD_C2832_HW_SPI
|
||||
|
||||
//#define U8GLIB_ST7565_NHD_C2832_HW_SPI
|
||||
|
||||
#define UI_LCD_WIDTH 128
|
||||
#define UI_LCD_HEIGHT 64
|
||||
|
||||
|
@ -225,13 +227,13 @@ Define the pin
|
|||
#define UI_DISPLAY_D6_PIN 44 // PINL.5, 40, D_D6
|
||||
#define UI_DISPLAY_D7_PIN 66 // PINK.4, 85, D_D7
|
||||
#define UI_DELAYPERCHAR 50
|
||||
|
||||
// Special pins for some u8g driven display
|
||||
|
||||
#define UI_DISPLAY_CS1 59
|
||||
#define UI_DISPLAY_CS2 59
|
||||
#define UI_DISPLAY_DI 59
|
||||
#define UI_DISPLAY_RW_PIN 59
|
||||
|
||||
// Special pins for some u8g driven display
|
||||
|
||||
#define UI_DISPLAY_CS1 59
|
||||
#define UI_DISPLAY_CS2 59
|
||||
#define UI_DISPLAY_DI 59
|
||||
#define UI_DISPLAY_RW_PIN 59
|
||||
#define UI_DISPLAY_RESET_PIN 59
|
||||
#endif
|
||||
|
||||
|
@ -447,7 +449,7 @@ void uiCheckSlowKeys(uint16_t &action) {
|
|||
}
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
|
2014
Repetier/uilang.cpp
2014
Repetier/uilang.cpp
File diff suppressed because it is too large
Load diff
6759
Repetier/uilang.h
6759
Repetier/uilang.h
File diff suppressed because it is too large
Load diff
1017
Repetier/uimenu.h
1017
Repetier/uimenu.h
File diff suppressed because it is too large
Load diff
Loading…
Reference in a new issue