Commit ce489f47 authored by MagoKimbra's avatar MagoKimbra

Update

parent 4de5ffee
...@@ -66,15 +66,15 @@ ...@@ -66,15 +66,15 @@
/***********************************************************************\ /***********************************************************************\
********************** Do not touch this section ********************** ********************** Do not touch this section **********************
***********************************************************************/ ***********************************************************************/
#if defined(CARTESIAN) #if ENABLED(CARTESIAN)
#include "Configuration_Cartesian.h" #include "Configuration_Cartesian.h"
#elif defined(COREXY) #elif ENABLED(COREXY)
#include "Configuration_Core.h" #include "Configuration_Core.h"
#elif defined(COREXZ) #elif ENABLED(COREXZ)
#include "Configuration_Core.h" #include "Configuration_Core.h"
#elif defined(DELTA) #elif ENABLED(DELTA)
#include "Configuration_Delta.h" #include "Configuration_Delta.h"
#elif defined(SCARA) #elif ENABLED(SCARA)
#include "Configuration_Scara.h" #include "Configuration_Scara.h"
#endif #endif
/***********************************************************************/ /***********************************************************************/
...@@ -110,7 +110,7 @@ ...@@ -110,7 +110,7 @@
* * * *
***********************************************************************/ ***********************************************************************/
//#define NPR2 //#define NPR2
#if defined(NPR2) #if ENABLED(NPR2)
#define COLOR_STEP {120,25,-65,-155} // CARTER ANGLE #define COLOR_STEP {120,25,-65,-155} // CARTER ANGLE
#define COLOR_SLOWRATE 170 // MICROSECOND delay for carter motor routine (Carter Motor Feedrate: upper value-slow feedrate) #define COLOR_SLOWRATE 170 // MICROSECOND delay for carter motor routine (Carter Motor Feedrate: upper value-slow feedrate)
#define COLOR_HOMERATE 4 // FEEDRATE for carter home #define COLOR_HOMERATE 4 // FEEDRATE for carter home
...@@ -227,7 +227,7 @@ ...@@ -227,7 +227,7 @@
// Comment the following line to disable PID and enable bang-bang. // Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP #define PIDTEMP
#ifdef PIDTEMP #if ENABLED(PIDTEMP)
//#define PID_DEBUG // Sends debug data to the serial port. //#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
...@@ -266,7 +266,7 @@ ...@@ -266,7 +266,7 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port. //#define PID_BED_DEBUG // Sends debug data to the serial port.
#ifdef PIDTEMPBED #if ENABLED(PIDTEMPBED)
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER // limit for the integral term #define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER // limit for the integral term
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
...@@ -363,7 +363,7 @@ ...@@ -363,7 +363,7 @@
// //
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib // ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
//#define ELB_FULL_GRAPHIC_CONTROLLER //#define ELB_FULL_GRAPHIC_CONTROLLER
//#define SDCARDDETECTINVERTED //#define SD_DETECT_INVERTED
// The RepRapDiscount Smart Controller (white PCB) // The RepRapDiscount Smart Controller (white PCB)
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller // http://reprap.org/wiki/RepRapDiscount_Smart_Controller
...@@ -485,13 +485,13 @@ ...@@ -485,13 +485,13 @@
// //
// M100 Free Memory Watcher // M100 Free Memory Watcher
// //
#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose //#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
//=========================================================================== //===========================================================================
//========================== EXTRA SETTINGS ON SD =========================== //========================== EXTRA SETTINGS ON SD ===========================
// Uncomment SD SETTINGS to enable the firmware to write some configuration, that require frequent update, on the SD card. // Uncomment SD SETTINGS to enable the firmware to write some configuration, that require frequent update, on the SD card.
//#define SD_SETTINGS //#define SD_SETTINGS
#ifdef SD_SETTINGS #if ENABLED(SD_SETTINGS)
#define SD_CFG_SECONDS 300 //seconds between update #define SD_CFG_SECONDS 300 //seconds between update
#define CFG_SD_FILE "INFO.CFG" //name of the configuration file #define CFG_SD_FILE "INFO.CFG" //name of the configuration file
#define CFG_SD_MAX_KEY_LEN 3+1 //icrease this if you add key name longer than the actual value. #define CFG_SD_MAX_KEY_LEN 3+1 //icrease this if you add key name longer than the actual value.
...@@ -501,7 +501,7 @@ ...@@ -501,7 +501,7 @@
//==================== Bowden Filament management =========================== //==================== Bowden Filament management ===========================
//#define EASY_LOAD //#define EASY_LOAD
#ifdef EASY_LOAD #if ENABLED(EASY_LOAD)
#define BOWDEN_LENGTH 250 // mm #define BOWDEN_LENGTH 250 // mm
#define LCD_PURGE_LENGTH 3 // mm #define LCD_PURGE_LENGTH 3 // mm
#define LCD_RETRACT_LENGTH 3 // mm #define LCD_RETRACT_LENGTH 3 // mm
...@@ -509,7 +509,7 @@ ...@@ -509,7 +509,7 @@
#define LCD_RETRACT_FEEDRATE 10 // mm/s #define LCD_RETRACT_FEEDRATE 10 // mm/s
#define LCD_LOAD_FEEDRATE 8 // mm/s #define LCD_LOAD_FEEDRATE 8 // mm/s
#define LCD_UNLOAD_FEEDRATE 8 // mm/s #define LCD_UNLOAD_FEEDRATE 8 // mm/s
#endif //EASY_LOAD #endif
//=========================================================================== //===========================================================================
...@@ -527,8 +527,11 @@ ...@@ -527,8 +527,11 @@
#define GUM_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255 #define GUM_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//=========================================================================== //===========================================================================
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas
**********************************************************************/
//============================= R/C Servo support ===========================
// Number of servos // Number of servos
// If you select a configuration below, this will receive a default value and does not need to be set manually // If you select a configuration below, this will receive a default value and does not need to be set manually
// set it manually if you have more servos than extruders and wish to manually control some // set it manually if you have more servos than extruders and wish to manually control some
...@@ -538,17 +541,21 @@ ...@@ -538,17 +541,21 @@
#if NUM_SERVOS > 0 #if NUM_SERVOS > 0
// Servo Endstops // Servo Endstops
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes. // This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
// Use M666 command to correct for switch height offset to actual nozzle height. Store that setting with M500. // Use M666 H to set the z-probe vertical offset from the nozzle. Store that setting with M500.
// // Define nr servo for endstop -1 not define. Servo index start 0
#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1 #define X_ENDSTOP_SERVO_NR -1
#define SERVO_ENDSTOP_ANGLES {0,0,0,0,90,0} // X,Y,Z Axis Extend and Retract angles #define Y_ENDSTOP_SERVO_NR -1
#define Z_ENDSTOP_SERVO_NR 0
#define X_ENDSTOP_SERVO_ANGLES {0,0} // X Axis Extend and Retract angles
#define Y_ENDSTOP_SERVO_ANGLES {0,0} // Y Axis Extend and Retract angles
#define Z_ENDSTOP_SERVO_ANGLES {90,0} // Z Axis Extend and Retract angles
// Servo deactivation // Servo deactivation
// //
// With this option servos are powered only during movement, then turned off to prevent jitter. // With this option servos are powered only during movement, then turned off to prevent jitter.
//#define DEACTIVATE_SERVOS_AFTER_MOVE //#define DEACTIVATE_SERVOS_AFTER_MOVE
#ifdef DEACTIVATE_SERVOS_AFTER_MOVE #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
// Delay (in microseconds) before turning the servo off. This depends on the servo speed. // Delay (in microseconds) before turning the servo off. This depends on the servo speed.
// 300ms is a good value but you can try less delay. // 300ms is a good value but you can try less delay.
// If the servo can't reach the requested position, increase it. // If the servo can't reach the requested position, increase it.
...@@ -575,6 +582,7 @@ ...@@ -575,6 +582,7 @@
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2,3) #define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2,3)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel #define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation #define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
#define MEASURED_UPPER_LIMIT 2.00 //upper limit factor used for sensor reading validation in mm #define MEASURED_UPPER_LIMIT 2.00 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.35 //lower limit factor for sensor reading validation in mm #define MEASURED_LOWER_LIMIT 1.35 //lower limit factor for sensor reading validation in mm
...@@ -602,7 +610,7 @@ ...@@ -602,7 +610,7 @@
**********************************************************************/ **********************************************************************/
// Uncomment below to enable // Uncomment below to enable
//#define POWER_CONSUMPTION //#define POWER_CONSUMPTION
#ifdef POWER_CONSUMPTION #if ENABLED(POWER_CONSUMPTION)
#define POWER_VOLTAGE 12.00 //(V) The power supply OUT voltage #define POWER_VOLTAGE 12.00 //(V) The power supply OUT voltage
#define POWER_ZERO 2.54459 //(V) The /\V coming out from the sensor when no current flow. #define POWER_ZERO 2.54459 //(V) The /\V coming out from the sensor when no current flow.
#define POWER_SENSITIVITY 0.066 //(V/A) How much increase V for 1A of increase #define POWER_SENSITIVITY 0.066 //(V/A) How much increase V for 1A of increase
...@@ -660,7 +668,7 @@ ...@@ -660,7 +668,7 @@
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament //#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// It is assumed that when logic high = filament available // It is assumed that when logic high = filament available
// when logic low = filament run out // when logic low = filament run out
#ifdef FILAMENT_RUNOUT_SENSOR #if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FILRUNOUT_PIN_INVERTING = true; // Should be uncommented and true or false should assigned const bool FILRUNOUT_PIN_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600" // Script execute when filament run out #define FILAMENT_RUNOUT_SCRIPT "M600" // Script execute when filament run out
......
...@@ -17,7 +17,7 @@ ...@@ -17,7 +17,7 @@
//=============================Thermal Settings ============================ //=============================Thermal Settings ============================
//=========================================================================== //===========================================================================
#ifdef BED_LIMIT_SWITCHING #if ENABLED(BED_LIMIT_SWITCHING)
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS #define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
#endif #endif
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control #define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
...@@ -25,7 +25,7 @@ ...@@ -25,7 +25,7 @@
/** /**
* Thermal Protection parameters * Thermal Protection parameters
*/ */
#ifdef THERMAL_PROTECTION_HOTENDS #if ENABLED(THERMAL_PROTECTION_HOTENDS)
#define THERMAL_PROTECTION_PERIOD 40 // Seconds #define THERMAL_PROTECTION_PERIOD 40 // Seconds
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius #define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
...@@ -39,7 +39,7 @@ ...@@ -39,7 +39,7 @@
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius #define WATCH_TEMP_INCREASE 4 // Degrees Celsius
#endif #endif
#ifdef THERMAL_PROTECTION_BED #if ENABLED(THERMAL_PROTECTION_BED)
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds #define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
#endif #endif
...@@ -56,7 +56,7 @@ ...@@ -56,7 +56,7 @@
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
*/ */
#define AUTOTEMP #define AUTOTEMP
#ifdef AUTOTEMP #if ENABLED(AUTOTEMP)
#define AUTOTEMP_OLDWEIGHT 0.98 #define AUTOTEMP_OLDWEIGHT 0.98
#endif #endif
...@@ -140,7 +140,7 @@ ...@@ -140,7 +140,7 @@
// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder. // On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
//#define Z_DUAL_STEPPER_DRIVERS //#define Z_DUAL_STEPPER_DRIVERS
#ifdef Z_DUAL_STEPPER_DRIVERS #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
// Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper. // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
// That way the machine is capable to align the bed during home, since both Z steppers are homed. // That way the machine is capable to align the bed during home, since both Z steppers are homed.
...@@ -157,7 +157,7 @@ ...@@ -157,7 +157,7 @@
// #define Z_DUAL_ENDSTOPS // #define Z_DUAL_ENDSTOPS
#ifdef Z_DUAL_ENDSTOPS #if ENABLED(Z_DUAL_ENDSTOPS)
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36) #define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
const bool Z2_MAX_ENDSTOP_INVERTING = false; const bool Z2_MAX_ENDSTOP_INVERTING = false;
#define DISABLE_XMAX_ENDSTOP //Better to disable the XMAX to avoid conflict. Just rename "XMAX_ENDSTOP" by the endstop you are using for Z2 axis. #define DISABLE_XMAX_ENDSTOP //Better to disable the XMAX to avoid conflict. Just rename "XMAX_ENDSTOP" by the endstop you are using for Z2 axis.
...@@ -176,7 +176,7 @@ ...@@ -176,7 +176,7 @@
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage // prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. // allowing faster printing speeds.
//#define DUAL_X_CARRIAGE //#define DUAL_X_CARRIAGE
#ifdef DUAL_X_CARRIAGE #if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage // Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop; // Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop. // the second x-carriage always homes to the maximum endstop.
...@@ -242,7 +242,7 @@ ...@@ -242,7 +242,7 @@
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
#define DEFAULT_MINTRAVELFEEDRATE 0.0 #define DEFAULT_MINTRAVELFEEDRATE 0.0
#ifdef ULTIPANEL #if ENABLED(ULTIPANEL)
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel #define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel
#define ULTIPANEL_FEEDMULTIPLY // Comment to disable setting feedrate multiplier via encoder #define ULTIPANEL_FEEDMULTIPLY // Comment to disable setting feedrate multiplier via encoder
#endif #endif
...@@ -291,15 +291,14 @@ ...@@ -291,15 +291,14 @@
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/ //#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again #define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted // Some RAMPS and other boards don't detect when an SD card is inserted. You can work
// You can get round this by connecting a push button or single throw switch to the pin defined as SDCARDCARDDETECT // around this by connecting a push button or single throw switch to the pin defined
// in the pins.h file. When using a push button pulling the pin to ground this will need inverted. This setting should // as SD_DETECT_PIN in your board's pins definitions.
// be commented out otherwise // This setting should be disabled unless you are using a push button, pulling the pin to ground.
#ifndef ELB_FULL_GRAPHIC_CONTROLLER // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
#define SDCARDDETECTINVERTED #define SD_DETECT_INVERTED
#endif
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers? #define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place. #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
...@@ -312,7 +311,7 @@ ...@@ -312,7 +311,7 @@
// Show a progress bar on HD44780 LCDs for SD printing // Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR //#define LCD_PROGRESS_BAR
#ifdef LCD_PROGRESS_BAR #if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar // Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 5000 #define PROGRESS_BAR_BAR_TIME 5000
// Amount of time (ms) to show the status message // Amount of time (ms) to show the status message
...@@ -335,7 +334,7 @@ ...@@ -335,7 +334,7 @@
#endif // SDSUPPORT #endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts: // for dogm lcd displays you can choose some additional fonts:
#ifdef DOGLCD #if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT // save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana // we don't have a big font for Cyrillic, Kana
//#define USE_BIG_EDIT_FONT //#define USE_BIG_EDIT_FONT
...@@ -348,7 +347,7 @@ ...@@ -348,7 +347,7 @@
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation. // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
//#define USE_WATCHDOG //#define USE_WATCHDOG
#ifdef USE_WATCHDOG #if ENABLED(USE_WATCHDOG)
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on. // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset. // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled. // However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
...@@ -359,8 +358,9 @@ ...@@ -359,8 +358,9 @@
// it can e.g. be used to change z-positions in the print startup phase in real-time // it can e.g. be used to change z-positions in the print startup phase in real-time
// does not respect endstops! // does not respect endstops!
//#define BABYSTEPPING //#define BABYSTEPPING
#ifdef BABYSTEPPING #if ENABLED(BABYSTEPPING)
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions #define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
//not implemented for CoreXY and deltabots!
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z #define BABYSTEP_INVERT_Z false //true for inverse movements in Z
#define BABYSTEP_Z_MULTIPLICATOR 2 //faster z movements #define BABYSTEP_Z_MULTIPLICATOR 2 //faster z movements
#endif #endif
...@@ -374,7 +374,7 @@ ...@@ -374,7 +374,7 @@
// so: v ^ 2 is proportional to number of steps we advance the extruder // so: v ^ 2 is proportional to number of steps we advance the extruder
//#define ADVANCE //#define ADVANCE
#ifdef ADVANCE #if ENABLED(ADVANCE)
#define EXTRUDER_ADVANCE_K .0 #define EXTRUDER_ADVANCE_K .0
#define D_FILAMENT 2.85 #define D_FILAMENT 2.85
#define STEPS_MM_E 836 #define STEPS_MM_E 836
...@@ -399,7 +399,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of ...@@ -399,7 +399,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of
// The number of linear motions that can be in the plan at any give time. // The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering. // THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else #else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
...@@ -426,7 +426,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of ...@@ -426,7 +426,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of
// the moves are than replaced by the firmware controlled ones. // the moves are than replaced by the firmware controlled ones.
//#define FWRETRACT //ONLY PARTIALLY TESTED //#define FWRETRACT //ONLY PARTIALLY TESTED
#ifdef FWRETRACT #if ENABLED(FWRETRACT)
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
#define RETRACT_LENGTH 3 //default retract length (positive mm) #define RETRACT_LENGTH 3 //default retract length (positive mm)
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
...@@ -438,9 +438,9 @@ const unsigned int dropsegments = 5; // everything with less than this number of ...@@ -438,9 +438,9 @@ const unsigned int dropsegments = 5; // everything with less than this number of
#endif #endif
// Add support for filament exchange support M600; requires display // Add support for filament exchange support M600; requires display
#ifdef ULTIPANEL #if ENABLED(ULTIPANEL)
#define FILAMENTCHANGEENABLE //#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE #if ENABLED(FILAMENTCHANGEENABLE)
#define FILAMENTCHANGE_XPOS 3 #define FILAMENTCHANGE_XPOS 3
#define FILAMENTCHANGE_YPOS 3 #define FILAMENTCHANGE_YPOS 3
#define FILAMENTCHANGE_ZADD 10 #define FILAMENTCHANGE_ZADD 10
...@@ -456,7 +456,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of ...@@ -456,7 +456,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of
******************************************************************************/ ******************************************************************************/
//#define HAVE_TMCDRIVER //#define HAVE_TMCDRIVER
#ifdef HAVE_TMCDRIVER #if ENABLED(HAVE_TMCDRIVER)
// #define X_IS_TMC // #define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA #define X_MAX_CURRENT 1000 //in mA
...@@ -516,7 +516,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of ...@@ -516,7 +516,7 @@ const unsigned int dropsegments = 5; // everything with less than this number of
******************************************************************************/ ******************************************************************************/
//#define HAVE_L6470DRIVER //#define HAVE_L6470DRIVER
#ifdef HAVE_L6470DRIVER #if ENABLED(HAVE_L6470DRIVER)
// #define X_IS_L6470 // #define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps #define X_MICROSTEPS 16 //number of microsteps
......
...@@ -46,7 +46,7 @@ void idle(bool ignore_stepper_queue = false); ...@@ -46,7 +46,7 @@ void idle(bool ignore_stepper_queue = false);
void manage_inactivity(bool ignore_stepper_queue=false); void manage_inactivity(bool ignore_stepper_queue=false);
#if defined(DUAL_X_CARRIAGE) && HAS_X_ENABLE && HAS_X2_ENABLE #if ENABLED(DUAL_X_CARRIAGE) && HAS_X_ENABLE && HAS_X2_ENABLE
#define enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0) #define enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0)
#define disable_x() do { X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0) #define disable_x() do { X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0)
#elif HAS_X_ENABLE #elif HAS_X_ENABLE
...@@ -58,7 +58,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); ...@@ -58,7 +58,7 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#endif #endif
#if HAS_Y_ENABLE #if HAS_Y_ENABLE
#ifdef Y_DUAL_STEPPER_DRIVERS #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
#define enable_y() { Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); } #define enable_y() { Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); }
#define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; } #define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#else #else
...@@ -71,7 +71,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); ...@@ -71,7 +71,7 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#endif #endif
#if HAS_Z_ENABLE #if HAS_Z_ENABLE
#ifdef Z_DUAL_STEPPER_DRIVERS #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#define enable_z() { Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); } #define enable_z() { Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }
#define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } #define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#else #else
...@@ -138,7 +138,7 @@ void disable_all_steppers(); ...@@ -138,7 +138,7 @@ void disable_all_steppers();
void FlushSerialRequestResend(); void FlushSerialRequestResend();
void ok_to_send(); void ok_to_send();
#ifdef DELTA #if ENABLED(DELTA)
float probe_bed(float x, float y); float probe_bed(float x, float y);
void set_delta_constants(); void set_delta_constants();
void adj_tower_delta(int tower); void adj_tower_delta(int tower);
...@@ -166,7 +166,7 @@ void ok_to_send(); ...@@ -166,7 +166,7 @@ void ok_to_send();
extern float delta_radius; extern float delta_radius;
extern float delta_diagonal_rod; extern float delta_diagonal_rod;
#endif #endif
#ifdef SCARA #if ENABLED(SCARA)
void calculate_delta(float cartesian[3]); void calculate_delta(float cartesian[3]);
void calculate_SCARA_forward_Transform(float f_scara[3]); void calculate_SCARA_forward_Transform(float f_scara[3]);
#endif #endif
...@@ -174,7 +174,7 @@ void prepare_move(); ...@@ -174,7 +174,7 @@ void prepare_move();
void kill(const char *); void kill(const char *);
void Stop(); void Stop();
#ifdef FILAMENT_RUNOUT_SENSOR #if ENABLED(FILAMENT_RUNOUT_SENSOR)
void filrunout(); void filrunout();
#endif #endif
...@@ -203,7 +203,7 @@ void clamp_to_software_endstops(float target[3]); ...@@ -203,7 +203,7 @@ void clamp_to_software_endstops(float target[3]);
extern millis_t previous_cmd_ms; extern millis_t previous_cmd_ms;
inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); } inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
#ifdef FAST_PWM_FAN #if ENABLED(FAST_PWM_FAN)
void setPwmFrequency(uint8_t pin, int val); void setPwmFrequency(uint8_t pin, int val);
#endif #endif
...@@ -233,22 +233,22 @@ extern float home_offset[3]; ...@@ -233,22 +233,22 @@ extern float home_offset[3];
extern float hotend_offset[NUM_HOTEND_OFFSETS][HOTENDS]; extern float hotend_offset[NUM_HOTEND_OFFSETS][HOTENDS];
#endif // HOTENDS > 1 #endif // HOTENDS > 1
#ifdef NPR2 #if ENABLED(NPR2)
extern int old_color; // old color for system NPR2 extern int old_color; // old color for system NPR2
#endif #endif
#ifdef DELTA #if ENABLED(DELTA)
extern float z_probe_offset[3]; extern float z_probe_offset[3];
extern float endstop_adj[3]; extern float endstop_adj[3];
extern float tower_adj[6]; extern float tower_adj[6];
extern float delta_radius; extern float delta_radius;
extern float delta_diagonal_rod; extern float delta_diagonal_rod;
extern float delta_segments_per_second; extern float delta_segments_per_second;
#elif defined(Z_DUAL_ENDSTOPS) #elif ENABLED(Z_DUAL_ENDSTOPS)
extern float z_endstop_adj; extern float z_endstop_adj;
#endif #endif
#ifdef SCARA #if ENABLED(SCARA)
extern float axis_scaling[3]; // Build size scaling extern float axis_scaling[3]; // Build size scaling
#endif #endif
...@@ -260,22 +260,22 @@ extern float zprobe_zoffset; ...@@ -260,22 +260,22 @@ extern float zprobe_zoffset;
// Lifetime stats // Lifetime stats
extern unsigned long printer_usage_seconds; //this can old about 136 year before go overflow. If you belive that you can live more than this please contact me. extern unsigned long printer_usage_seconds; //this can old about 136 year before go overflow. If you belive that you can live more than this please contact me.
#ifdef PREVENT_DANGEROUS_EXTRUDE #if ENABLED(PREVENT_DANGEROUS_EXTRUDE)
extern float extrude_min_temp; extern float extrude_min_temp;
#endif #endif
extern int fanSpeed; extern int fanSpeed;
#ifdef BARICUDA #if ENABLED(BARICUDA)
extern int ValvePressure; extern int ValvePressure;
extern int EtoPPressure; extern int EtoPPressure;
#endif #endif
#ifdef FAN_SOFT_PWM #if ENABLED(FAN_SOFT_PWM)
extern unsigned char fanSpeedSoftPwm; extern unsigned char fanSpeedSoftPwm;
#endif #endif
#if HAS_FILAMENT_SENSOR #if ENABLED(FILAMENT_SENSOR)
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75 extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
extern float filament_width_meas; //holds the filament diameter as accurately measured extern float filament_width_meas; //holds the filament diameter as accurately measured
...@@ -292,26 +292,26 @@ extern int fanSpeed; ...@@ -292,26 +292,26 @@ extern int fanSpeed;
extern unsigned long stoppower; extern unsigned long stoppower;
#endif #endif
#ifdef IDLE_OOZING_PREVENT #if ENABLED(IDLE_OOZING_PREVENT)
extern bool idleoozing_enabled; extern bool idleoozing_enabled;
#endif #endif
#ifdef FWRETRACT #if ENABLED(FWRETRACT)
extern bool autoretract_enabled; extern bool autoretract_enabled;
extern bool retracted[EXTRUDERS]; extern bool retracted[EXTRUDERS]; // extruder[n].retracted
extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift; extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift;
extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate; extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate;
#endif #endif
#ifdef EASY_LOAD #if ENABLED(EASY_LOAD)
extern bool allow_lengthy_extrude_once; // for load/unload extern bool allow_lengthy_extrude_once; // for load/unload
#endif #endif
#ifdef LASERBEAM #if ENABLED(LASERBEAM)
extern int laser_ttl_modulation; extern int laser_ttl_modulation;
#endif #endif
#if defined(SDSUPPORT) && defined(SD_SETTINGS) #if ENABLED(SDSUPPORT) && ENABLED(SD_SETTINGS)
extern millis_t config_last_update; extern millis_t config_last_update;
extern bool config_readed; extern bool config_readed;
#endif #endif
...@@ -323,12 +323,12 @@ extern millis_t print_job_stop_ms; ...@@ -323,12 +323,12 @@ extern millis_t print_job_stop_ms;
extern uint8_t active_extruder; extern uint8_t active_extruder;
extern uint8_t active_driver; extern uint8_t active_driver;
#ifdef DIGIPOT_I2C #if ENABLED(DIGIPOT_I2C)
extern void digipot_i2c_set_current( int channel, float current ); extern void digipot_i2c_set_current( int channel, float current );
extern void digipot_i2c_init(); extern void digipot_i2c_init();
#endif #endif
#ifdef FIRMWARE_TEST #if ENABLED(FIRMWARE_TEST)
void FirmwareTest(); void FirmwareTest();
#endif #endif
......
...@@ -23,7 +23,7 @@ ...@@ -23,7 +23,7 @@
#include "Marlin.h" #include "Marlin.h"
#include "MarlinSerial.h" #include "MarlinSerial.h"
#ifndef AT90USB #ifndef USBCON
// this next line disables the entire HardwareSerial.cpp, // this next line disables the entire HardwareSerial.cpp,
// this is so I can support Attiny series and any other chip without a UART // this is so I can support Attiny series and any other chip without a UART
#if defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H) #if defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)
...@@ -284,9 +284,9 @@ void MarlinSerial::printFloat(double number, uint8_t digits) { ...@@ -284,9 +284,9 @@ void MarlinSerial::printFloat(double number, uint8_t digits) {
MarlinSerial MSerial; MarlinSerial MSerial;
#endif // whole file #endif // whole file
#endif // !AT90USB #endif // !USBCON
// For AT90USB targets use the UART for BT interfacing // For AT90USB targets use the UART for BT interfacing
#if defined(AT90USB) && defined(BTENABLED) #if defined(USBCON) && ENABLED(BTENABLED)
HardwareSerial bt; HardwareSerial bt;
#endif #endif
...@@ -64,7 +64,7 @@ ...@@ -64,7 +64,7 @@
#define BYTE 0 #define BYTE 0
#ifndef AT90USB #ifndef USBCON
// Define constants and variables for buffering incoming serial data. We're // Define constants and variables for buffering incoming serial data. We're
// using a ring buffer (I think), in which rx_buffer_head is the index of the // using a ring buffer (I think), in which rx_buffer_head is the index of the
// location to which to write the next incoming character and rx_buffer_tail // location to which to write the next incoming character and rx_buffer_tail
...@@ -150,10 +150,10 @@ class MarlinSerial { //: public Stream ...@@ -150,10 +150,10 @@ class MarlinSerial { //: public Stream
}; };
extern MarlinSerial MSerial; extern MarlinSerial MSerial;
#endif // !AT90USB #endif // !USBCON
// Use the UART for BT in AT90USB configurations // Use the UART for BT in AT90USB configurations
#if defined(AT90USB) && defined(BTENABLED) #if defined(USBCON) && ENABLED(BTENABLED)
extern HardwareSerial bt; extern HardwareSerial bt;
#endif #endif
......
This diff is collapsed.
...@@ -19,10 +19,10 @@ ...@@ -19,10 +19,10 @@
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "Sd2Card.h" #include "Sd2Card.h"
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
#ifndef SOFTWARE_SPI #if DISABLED(SOFTWARE_SPI)
// functions for hardware SPI // functions for hardware SPI
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// make sure SPCR rate is in expected bits // make sure SPCR rate is in expected bits
...@@ -209,7 +209,7 @@ void Sd2Card::chipSelectHigh() { ...@@ -209,7 +209,7 @@ void Sd2Card::chipSelectHigh() {
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
void Sd2Card::chipSelectLow() { void Sd2Card::chipSelectLow() {
#ifndef SOFTWARE_SPI #if DISABLED(SOFTWARE_SPI)
spiInit(spiRate_); spiInit(spiRate_);
#endif // SOFTWARE_SPI #endif // SOFTWARE_SPI
digitalWrite(chipSelectPin_, LOW); digitalWrite(chipSelectPin_, LOW);
...@@ -297,7 +297,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { ...@@ -297,7 +297,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
pinMode(SPI_MOSI_PIN, OUTPUT); pinMode(SPI_MOSI_PIN, OUTPUT);
pinMode(SPI_SCK_PIN, OUTPUT); pinMode(SPI_SCK_PIN, OUTPUT);
#ifndef SOFTWARE_SPI #if DISABLED(SOFTWARE_SPI)
// SS must be in output mode even it is not chip select // SS must be in output mode even it is not chip select
pinMode(SS_PIN, OUTPUT); pinMode(SS_PIN, OUTPUT);
// set SS high - may be chip select for another SPI device // set SS high - may be chip select for another SPI device
...@@ -353,7 +353,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { ...@@ -353,7 +353,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
} }
chipSelectHigh(); chipSelectHigh();
#ifndef SOFTWARE_SPI #if DISABLED(SOFTWARE_SPI)
return setSckRate(sckRateID); return setSckRate(sckRateID);
#else // SOFTWARE_SPI #else // SOFTWARE_SPI
return true; return true;
...@@ -373,7 +373,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { ...@@ -373,7 +373,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
* the value zero, false, is returned for failure. * the value zero, false, is returned for failure.
*/ */
bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) { bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
#ifdef SD_CHECK_AND_RETRY #if ENABLED(SD_CHECK_AND_RETRY)
uint8_t retryCnt = 3; uint8_t retryCnt = 3;
// use address if not SDHC card // use address if not SDHC card
if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9; if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9;
...@@ -422,7 +422,7 @@ bool Sd2Card::readData(uint8_t *dst) { ...@@ -422,7 +422,7 @@ bool Sd2Card::readData(uint8_t *dst) {
return readData(dst, 512); return readData(dst, 512);
} }
#ifdef SD_CHECK_AND_RETRY #if ENABLED(SD_CHECK_AND_RETRY)
static const uint16_t crctab[] PROGMEM = { static const uint16_t crctab[] PROGMEM = {
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
...@@ -483,7 +483,7 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) { ...@@ -483,7 +483,7 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
// transfer data // transfer data
spiRead(dst, count); spiRead(dst, count);
#ifdef SD_CHECK_AND_RETRY #if ENABLED(SD_CHECK_AND_RETRY)
{ {
uint16_t calcCrc = CRC_CCITT(dst, count); uint16_t calcCrc = CRC_CCITT(dst, count);
uint16_t recvCrc = spiRec() << 8; uint16_t recvCrc = spiRec() << 8;
......
...@@ -19,7 +19,7 @@ ...@@ -19,7 +19,7 @@
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef Sd2Card_h #ifndef Sd2Card_h
#define Sd2Card_h #define Sd2Card_h
...@@ -125,7 +125,7 @@ uint8_t const SD_CARD_TYPE_SDHC = 3; ...@@ -125,7 +125,7 @@ uint8_t const SD_CARD_TYPE_SDHC = 3;
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// SPI pin definitions - do not edit here - change in SdFatConfig.h // SPI pin definitions - do not edit here - change in SdFatConfig.h
// //
#ifndef SOFTWARE_SPI #if DISABLED(SOFTWARE_SPI)
// hardware pin defs // hardware pin defs
/** The default chip select pin for the SD card is SS. */ /** The default chip select pin for the SD card is SS. */
uint8_t const SD_CHIP_SELECT_PIN = SS_PIN; uint8_t const SD_CHIP_SELECT_PIN = SS_PIN;
......
...@@ -19,7 +19,9 @@ ...@@ -19,7 +19,9 @@
*/ */
// Warning this file was generated by a program. // Warning this file was generated by a program.
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #include "macros.h"
#if ENABLED(SDSUPPORT)
#ifndef Sd2PinMap_h #ifndef Sd2PinMap_h
#define Sd2PinMap_h #define Sd2PinMap_h
...@@ -385,7 +387,7 @@ static const pin_map_t digitalPinMap[] = { ...@@ -385,7 +387,7 @@ static const pin_map_t digitalPinMap[] = {
#error unknown chip #error unknown chip
#endif // defined(__AVR_ATmega1280__) #endif // defined(__AVR_ATmega1280__)
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
static const uint8_t digitalPinCount = sizeof(digitalPinMap)/sizeof(pin_map_t); static const uint8_t digitalPinCount = COUNT(digitalPinMap);
uint8_t badPinNumber(void) uint8_t badPinNumber(void)
__attribute__((error("Pin number is too large or not a constant"))); __attribute__((error("Pin number is too large or not a constant")));
......
...@@ -19,7 +19,7 @@ ...@@ -19,7 +19,7 @@
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "SdBaseFile.h" #include "SdBaseFile.h"
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef SdBaseFile_h #ifndef SdBaseFile_h
#define SdBaseFile_h #define SdBaseFile_h
......
...@@ -22,7 +22,7 @@ ...@@ -22,7 +22,7 @@
* \brief configuration definitions * \brief configuration definitions
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef SdFatConfig_h #ifndef SdFatConfig_h
#define SdFatConfig_h #define SdFatConfig_h
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef SdFatStructs_h #ifndef SdFatStructs_h
#define SdFatStructs_h #define SdFatStructs_h
......
...@@ -19,7 +19,7 @@ ...@@ -19,7 +19,7 @@
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "SdFatUtil.h" #include "SdFatUtil.h"
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef SdFatUtil_h #ifndef SdFatUtil_h
#define SdFatUtil_h #define SdFatUtil_h
......
...@@ -19,7 +19,7 @@ ...@@ -19,7 +19,7 @@
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "SdFile.h" #include "SdFile.h"
/** Create a file object and open it in the current working directory. /** Create a file object and open it in the current working directory.
* *
......
...@@ -23,7 +23,7 @@ ...@@ -23,7 +23,7 @@
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "SdBaseFile.h" #include "SdBaseFile.h"
#include <Print.h> #include <Print.h>
#ifndef SdFile_h #ifndef SdFile_h
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef SdInfo_h #ifndef SdInfo_h
#define SdInfo_h #define SdInfo_h
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "SdVolume.h" #include "SdVolume.h"
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* <http://www.gnu.org/licenses/>. * <http://www.gnu.org/licenses/>.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#ifndef SdVolume_h #ifndef SdVolume_h
#define SdVolume_h #define SdVolume_h
/** /**
......
...@@ -3,7 +3,8 @@ ...@@ -3,7 +3,8 @@
Created by Tim Koster, August 21 2013. Created by Tim Koster, August 21 2013.
*/ */
#include "Marlin.h" #include "Marlin.h"
#ifdef BLINKM
#if ENABLED(BLINKM)
#include "blinkm.h" #include "blinkm.h"
......
...@@ -37,7 +37,7 @@ ...@@ -37,7 +37,7 @@
#define BOARD_MELZI 63 // Melzi #define BOARD_MELZI 63 // Melzi
#define BOARD_STB_11 64 // STB V1.1 #define BOARD_STB_11 64 // STB V1.1
#define BOARD_AZTEEG_X1 65 // Azteeg X1 #define BOARD_AZTEEG_X1 65 // Azteeg X1
#define BOARD_MELZI_1284 66 // Melzi with ATmega1284 (MaKr3d version) #define BOARD_MELZI_MAKR3D 66 // Melzi with ATmega1284 (MaKr3d version)
#define BOARD_AZTEEG_X3 67 // Azteeg X3 #define BOARD_AZTEEG_X3 67 // Azteeg X3
#define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro #define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro
......
...@@ -5,24 +5,24 @@ ...@@ -5,24 +5,24 @@
#if HAS_BUZZER #if HAS_BUZZER
void buzz(long duration, uint16_t freq) { void buzz(long duration, uint16_t freq) {
if (freq > 0) { if (freq > 0) {
#ifdef LCD_USE_I2C_BUZZER #if ENABLED(LCD_USE_I2C_BUZZER)
lcd_buzz(duration, freq); lcd_buzz(duration, freq);
#elif defined(BEEPER) && BEEPER >= 0 // on-board buzzers have no further condition #elif PIN_EXISTS(BEEPER) // on-board buzzers have no further condition
SET_OUTPUT(BEEPER); SET_OUTPUT(BEEPER_PIN);
#ifdef SPEAKER // a speaker needs a AC ore a pulsed DC #if ENABLED(SPEAKER) // a speaker needs a AC ore a pulsed DC
//tone(BEEPER, freq, duration); // needs a PWMable pin //tone(BEEPER_PIN, freq, duration); // needs a PWMable pin
unsigned int delay = 1000000 / freq / 2; unsigned int delay = 1000000 / freq / 2;
int i = duration * freq / 1000; int i = duration * freq / 1000;
while (i--) { while (i--) {
WRITE(BEEPER,HIGH); WRITE(BEEPER_PIN, HIGH);
delayMicroseconds(delay); delayMicroseconds(delay);
WRITE(BEEPER,LOW); WRITE(BEEPER_PIN, LOW);
delayMicroseconds(delay); delayMicroseconds(delay);
} }
#else // buzzer has its own resonator - needs a DC #else // buzzer has its own resonator - needs a DC
WRITE(BEEPER, HIGH); WRITE(BEEPER_PIN, HIGH);
delay(duration); delay(duration);
WRITE(BEEPER, LOW); WRITE(BEEPER_PIN, LOW);
#endif #endif
#else #else
delay(duration); delay(duration);
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#include "temperature.h" #include "temperature.h"
#include "language.h" #include "language.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
CardReader::CardReader() { CardReader::CardReader() {
filesize = 0; filesize = 0;
...@@ -126,7 +126,7 @@ void CardReader::ls() { ...@@ -126,7 +126,7 @@ void CardReader::ls() {
lsDive("", root); lsDive("", root);
} }
#ifdef LONG_FILENAME_HOST_SUPPORT #if ENABLED(LONG_FILENAME_HOST_SUPPORT)
/** /**
* Get a long pretty path based on a DOS 8.3 path * Get a long pretty path based on a DOS 8.3 path
...@@ -191,7 +191,7 @@ void CardReader::initsd() { ...@@ -191,7 +191,7 @@ void CardReader::initsd() {
cardOK = false; cardOK = false;
if (root.isOpen()) root.close(); if (root.isOpen()) root.close();
#ifdef SDSLOW #if ENABLED(SDSLOW)
#define SPI_SPEED SPI_HALF_SPEED #define SPI_SPEED SPI_HALF_SPEED
#else #else
#define SPI_SPEED SPI_FULL_SPEED #define SPI_SPEED SPI_FULL_SPEED
...@@ -612,7 +612,7 @@ void CardReader::chdir(const char * relpath) { ...@@ -612,7 +612,7 @@ void CardReader::chdir(const char * relpath) {
if (workDir.isOpen()) parent = &workDir; if (workDir.isOpen()) parent = &workDir;
if (!newfile.open(*parent, relpath, O_READ)) { if (!newfile.open(*parent, relpath, O_READ)) {
ECHO_LMV(ER, MSG_SD_CANT_ENTER_SUBDIR, relpath); ECHO_LMV(DB, MSG_SD_CANT_ENTER_SUBDIR, relpath);
} }
else { else {
if (workDirDepth < MAX_DIR_DEPTH) { if (workDirDepth < MAX_DIR_DEPTH) {
......
#ifndef CARDREADER_H #ifndef CARDREADER_H
#define CARDREADER_H #define CARDREADER_H
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#define MAX_DIR_DEPTH 10 // Maximum folder depth #define MAX_DIR_DEPTH 10 // Maximum folder depth
...@@ -30,11 +30,11 @@ public: ...@@ -30,11 +30,11 @@ public:
void getStatus(); void getStatus();
void printingHasFinished(); void printingHasFinished();
#ifdef LONG_FILENAME_HOST_SUPPORT #if ENABLED(LONG_FILENAME_HOST_SUPPORT)
void printLongPath(char *path); void printLongPath(char *path);
#endif #endif
void getfilename(uint16_t nr, const char* const match = NULL); void getfilename(uint16_t nr, const char* const match=NULL);
uint16_t getnrfilenames(); uint16_t getnrfilenames();
void getAbsFilename(char *t); void getAbsFilename(char *t);
...@@ -83,11 +83,11 @@ extern CardReader card; ...@@ -83,11 +83,11 @@ extern CardReader card;
#define IS_SD_PRINTING (card.sdprinting) #define IS_SD_PRINTING (card.sdprinting)
#if (SDCARDDETECT > -1) #if PIN_EXISTS(SD_DETECT)
#ifdef SDCARDDETECTINVERTED #if ENABLED(SD_DETECT_INVERTED)
#define IS_SD_INSERTED (READ(SDCARDDETECT) != 0) #define IS_SD_INSERTED (READ(SD_DETECT_PIN) != 0)
#else #else
#define IS_SD_INSERTED (READ(SDCARDDETECT) == 0) #define IS_SD_INSERTED (READ(SD_DETECT_PIN) == 0)
#endif #endif
#else #else
//No card detect line? Assume the card is inserted. //No card detect line? Assume the card is inserted.
......
...@@ -8,7 +8,7 @@ ...@@ -8,7 +8,7 @@
#ifndef COMUNICATION_H #ifndef COMUNICATION_H
#define COMUNICATION_H #define COMUNICATION_H
#ifdef AT90USB #ifdef USBCON
#include "HardwareSerial.h" #include "HardwareSerial.h"
#endif #endif
......
This diff is collapsed.
...@@ -103,7 +103,7 @@ ...@@ -103,7 +103,7 @@
#include "ultralcd.h" #include "ultralcd.h"
#include "configuration_store.h" #include "configuration_store.h"
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
#include "cardreader.h" #include "cardreader.h"
#endif #endif
...@@ -137,7 +137,7 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) { ...@@ -137,7 +137,7 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) {
#define EEPROM_OFFSET 100 #define EEPROM_OFFSET 100
#ifdef EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS)
void Config_StoreSettings() { void Config_StoreSettings() {
float dummy = 0.0f; float dummy = 0.0f;
...@@ -158,7 +158,7 @@ void Config_StoreSettings() { ...@@ -158,7 +158,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, max_e_jerk); EEPROM_WRITE_VAR(i, max_e_jerk);
EEPROM_WRITE_VAR(i, home_offset); EEPROM_WRITE_VAR(i, home_offset);
#ifndef DELTA #if DISABLED(DELTA)
EEPROM_WRITE_VAR(i, zprobe_zoffset); EEPROM_WRITE_VAR(i, zprobe_zoffset);
#endif #endif
...@@ -166,7 +166,7 @@ void Config_StoreSettings() { ...@@ -166,7 +166,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, hotend_offset); EEPROM_WRITE_VAR(i, hotend_offset);
#endif #endif
#ifdef DELTA #if ENABLED(DELTA)
EEPROM_WRITE_VAR(i, endstop_adj); EEPROM_WRITE_VAR(i, endstop_adj);
EEPROM_WRITE_VAR(i, delta_radius); EEPROM_WRITE_VAR(i, delta_radius);
EEPROM_WRITE_VAR(i, delta_diagonal_rod); EEPROM_WRITE_VAR(i, delta_diagonal_rod);
...@@ -174,11 +174,11 @@ void Config_StoreSettings() { ...@@ -174,11 +174,11 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, tower_adj); EEPROM_WRITE_VAR(i, tower_adj);
EEPROM_WRITE_VAR(i, diagrod_adj); EEPROM_WRITE_VAR(i, diagrod_adj);
EEPROM_WRITE_VAR(i, z_probe_offset); EEPROM_WRITE_VAR(i, z_probe_offset);
#elif defined(Z_DUAL_ENDSTOPS) #elif ENABLED(Z_DUAL_ENDSTOPS)
EEPROM_WRITE_VAR(i, z_endstop_adj); // 1 floats EEPROM_WRITE_VAR(i, z_endstop_adj); // 1 floats
#endif #endif
#ifndef ULTIPANEL #if DISABLED(ULTIPANEL)
int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED, int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED,
absPreheatHotendTemp = ABS_PREHEAT_HOTEND_TEMP, absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP, absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED, absPreheatHotendTemp = ABS_PREHEAT_HOTEND_TEMP, absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP, absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED,
gumPreheatHotendTemp = GUM_PREHEAT_HOTEND_TEMP, gumPreheatHPBTemp = GUM_PREHEAT_HPB_TEMP, gumPreheatFanSpeed = GUM_PREHEAT_FAN_SPEED; gumPreheatHotendTemp = GUM_PREHEAT_HOTEND_TEMP, gumPreheatHPBTemp = GUM_PREHEAT_HPB_TEMP, gumPreheatFanSpeed = GUM_PREHEAT_FAN_SPEED;
...@@ -194,7 +194,7 @@ void Config_StoreSettings() { ...@@ -194,7 +194,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, gumPreheatHPBTemp); EEPROM_WRITE_VAR(i, gumPreheatHPBTemp);
EEPROM_WRITE_VAR(i, gumPreheatFanSpeed); EEPROM_WRITE_VAR(i, gumPreheatFanSpeed);
#ifdef PIDTEMP #if ENABLED(PIDTEMP)
for (int e = 0; e < HOTENDS; e++) { for (int e = 0; e < HOTENDS; e++) {
EEPROM_WRITE_VAR(i, PID_PARAM(Kp, e)); EEPROM_WRITE_VAR(i, PID_PARAM(Kp, e));
EEPROM_WRITE_VAR(i, PID_PARAM(Ki, e)); EEPROM_WRITE_VAR(i, PID_PARAM(Ki, e));
...@@ -202,22 +202,22 @@ void Config_StoreSettings() { ...@@ -202,22 +202,22 @@ void Config_StoreSettings() {
} }
#endif #endif
#ifdef PIDTEMPBED #if ENABLED(PIDTEMPBED)
EEPROM_WRITE_VAR(i, bedKp); EEPROM_WRITE_VAR(i, bedKp);
EEPROM_WRITE_VAR(i, bedKi); EEPROM_WRITE_VAR(i, bedKi);
EEPROM_WRITE_VAR(i, bedKd); EEPROM_WRITE_VAR(i, bedKd);
#endif #endif
#ifndef HAS_LCD_CONTRAST #if DISABLED(HAS_LCD_CONTRAST)
const int lcd_contrast = 32; const int lcd_contrast = 32;
#endif #endif
EEPROM_WRITE_VAR(i, lcd_contrast); EEPROM_WRITE_VAR(i, lcd_contrast);
#ifdef SCARA #if ENABLED(SCARA)
EEPROM_WRITE_VAR(i, axis_scaling); // 3 floats EEPROM_WRITE_VAR(i, axis_scaling); // 3 floats
#endif #endif
#ifdef FWRETRACT #if ENABLED(FWRETRACT)
EEPROM_WRITE_VAR(i, autoretract_enabled); EEPROM_WRITE_VAR(i, autoretract_enabled);
EEPROM_WRITE_VAR(i, retract_length); EEPROM_WRITE_VAR(i, retract_length);
#if EXTRUDERS > 1 #if EXTRUDERS > 1
...@@ -246,7 +246,7 @@ void Config_StoreSettings() { ...@@ -246,7 +246,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, dummy); EEPROM_WRITE_VAR(i, dummy);
} }
#ifdef IDLE_OOZING_PREVENT #if ENABLED(IDLE_OOZING_PREVENT)
EEPROM_WRITE_VAR(i, idleoozing_enabled); EEPROM_WRITE_VAR(i, idleoozing_enabled);
#endif #endif
...@@ -295,7 +295,7 @@ void Config_RetrieveSettings() { ...@@ -295,7 +295,7 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, max_e_jerk); EEPROM_READ_VAR(i, max_e_jerk);
EEPROM_READ_VAR(i, home_offset); EEPROM_READ_VAR(i, home_offset);
#ifndef DELTA #if DISABLED(DELTA)
EEPROM_READ_VAR(i, zprobe_zoffset); EEPROM_READ_VAR(i, zprobe_zoffset);
#endif #endif
...@@ -303,7 +303,7 @@ void Config_RetrieveSettings() { ...@@ -303,7 +303,7 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, hotend_offset); EEPROM_READ_VAR(i, hotend_offset);
#endif #endif
#ifdef DELTA #if ENABLED(DELTA)
EEPROM_READ_VAR(i, endstop_adj); EEPROM_READ_VAR(i, endstop_adj);
EEPROM_READ_VAR(i, delta_radius); EEPROM_READ_VAR(i, delta_radius);
EEPROM_READ_VAR(i, delta_diagonal_rod); EEPROM_READ_VAR(i, delta_diagonal_rod);
...@@ -315,7 +315,7 @@ void Config_RetrieveSettings() { ...@@ -315,7 +315,7 @@ void Config_RetrieveSettings() {
set_delta_constants(); set_delta_constants();
#endif //DELTA #endif //DELTA
#ifndef ULTIPANEL #if DISABLED(ULTIPANEL)
int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed, int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed,
absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed,
gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed; gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed;
...@@ -331,7 +331,7 @@ void Config_RetrieveSettings() { ...@@ -331,7 +331,7 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, gumPreheatHPBTemp); EEPROM_READ_VAR(i, gumPreheatHPBTemp);
EEPROM_READ_VAR(i, gumPreheatFanSpeed); EEPROM_READ_VAR(i, gumPreheatFanSpeed);
#ifdef PIDTEMP #if ENABLED(PIDTEMP)
for (int8_t e = 0; e < HOTENDS; e++) { for (int8_t e = 0; e < HOTENDS; e++) {
EEPROM_READ_VAR(i, PID_PARAM(Kp, e)); EEPROM_READ_VAR(i, PID_PARAM(Kp, e));
EEPROM_READ_VAR(i, PID_PARAM(Ki, e)); EEPROM_READ_VAR(i, PID_PARAM(Ki, e));
...@@ -339,23 +339,23 @@ void Config_RetrieveSettings() { ...@@ -339,23 +339,23 @@ void Config_RetrieveSettings() {
} }
#endif // PIDTEMP #endif // PIDTEMP
#ifdef PIDTEMPBED #if ENABLED(PIDTEMPBED)
EEPROM_READ_VAR(i, bedKp); EEPROM_READ_VAR(i, bedKp);
EEPROM_READ_VAR(i, bedKi); EEPROM_READ_VAR(i, bedKi);
EEPROM_READ_VAR(i, bedKd); EEPROM_READ_VAR(i, bedKd);
#endif #endif
#ifndef HAS_LCD_CONTRAST #if DISABLED(HAS_LCD_CONTRAST)
int lcd_contrast; int lcd_contrast;
#endif #endif
EEPROM_READ_VAR(i, lcd_contrast); EEPROM_READ_VAR(i, lcd_contrast);
#ifdef SCARA #if ENABLED(SCARA)
EEPROM_READ_VAR(i, axis_scaling); // 3 floats EEPROM_READ_VAR(i, axis_scaling); // 3 floats
#endif #endif
#ifdef FWRETRACT #if ENABLED(FWRETRACT)
EEPROM_READ_VAR(i, autoretract_enabled); EEPROM_READ_VAR(i, autoretract_enabled);
EEPROM_READ_VAR(i, retract_length); EEPROM_READ_VAR(i, retract_length);
#if EXTRUDERS > 1 #if EXTRUDERS > 1
...@@ -383,7 +383,7 @@ void Config_RetrieveSettings() { ...@@ -383,7 +383,7 @@ void Config_RetrieveSettings() {
calculate_volumetric_multipliers(); calculate_volumetric_multipliers();
#ifdef IDLE_OOZING_PREVENT #if ENABLED(IDLE_OOZING_PREVENT)
EEPROM_READ_VAR(i, idleoozing_enabled); EEPROM_READ_VAR(i, idleoozing_enabled);
#endif #endif
...@@ -396,7 +396,7 @@ void Config_RetrieveSettings() { ...@@ -396,7 +396,7 @@ void Config_RetrieveSettings() {
ECHO_EM(" bytes)"); ECHO_EM(" bytes)");
} }
#ifdef EEPROM_CHITCHAT #if ENABLED(EEPROM_CHITCHAT)
Config_PrintSettings(); Config_PrintSettings();
#endif #endif
} }
...@@ -412,7 +412,7 @@ void Config_ResetDefault() { ...@@ -412,7 +412,7 @@ void Config_ResetDefault() {
long tmp3[] = DEFAULT_MAX_ACCELERATION; long tmp3[] = DEFAULT_MAX_ACCELERATION;
long tmp4[] = DEFAULT_RETRACT_ACCELERATION; long tmp4[] = DEFAULT_RETRACT_ACCELERATION;
long tmp5[] = DEFAULT_EJERK; long tmp5[] = DEFAULT_EJERK;
#ifdef PIDTEMP #if ENABLED(PIDTEMP)
float tmp6[] = DEFAULT_Kp; float tmp6[] = DEFAULT_Kp;
float tmp7[] = DEFAULT_Ki; float tmp7[] = DEFAULT_Ki;
float tmp8[] = DEFAULT_Kd; float tmp8[] = DEFAULT_Kd;
...@@ -469,7 +469,7 @@ void Config_ResetDefault() { ...@@ -469,7 +469,7 @@ void Config_ResetDefault() {
} }
} }
#ifdef SCARA #if ENABLED(SCARA)
for (int8_t i = 0; i < NUM_AXIS; i++) { for (int8_t i = 0; i < NUM_AXIS; i++) {
if (i < COUNT(axis_scaling)) if (i < COUNT(axis_scaling))
axis_scaling[i] = 1; axis_scaling[i] = 1;
...@@ -488,13 +488,13 @@ void Config_ResetDefault() { ...@@ -488,13 +488,13 @@ void Config_ResetDefault() {
max_z_jerk = DEFAULT_ZJERK; max_z_jerk = DEFAULT_ZJERK;
home_offset[X_AXIS] = home_offset[Y_AXIS] = home_offset[Z_AXIS] = 0; home_offset[X_AXIS] = home_offset[Y_AXIS] = home_offset[Z_AXIS] = 0;
#ifdef ENABLE_AUTO_BED_LEVELING #if ENABLED(ENABLE_AUTO_BED_LEVELING)
zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER; zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER;
#elif !defined(DELTA) #elif !defined(DELTA)
zprobe_zoffset = 0; zprobe_zoffset = 0;
#endif #endif
#ifdef DELTA #if ENABLED(DELTA)
delta_radius = DEFAULT_DELTA_RADIUS; delta_radius = DEFAULT_DELTA_RADIUS;
delta_diagonal_rod = DEFAULT_DELTA_DIAGONAL_ROD; delta_diagonal_rod = DEFAULT_DELTA_DIAGONAL_ROD;
endstop_adj[0] = TOWER_A_ENDSTOP_ADJ; endstop_adj[0] = TOWER_A_ENDSTOP_ADJ;
...@@ -514,7 +514,7 @@ void Config_ResetDefault() { ...@@ -514,7 +514,7 @@ void Config_ResetDefault() {
set_delta_constants(); set_delta_constants();
#endif #endif
#ifdef ULTIPANEL #if ENABLED(ULTIPANEL)
plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP; plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP;
plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP; plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP;
plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED; plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED;
...@@ -526,11 +526,11 @@ void Config_ResetDefault() { ...@@ -526,11 +526,11 @@ void Config_ResetDefault() {
gumPreheatFanSpeed = GUM_PREHEAT_FAN_SPEED; gumPreheatFanSpeed = GUM_PREHEAT_FAN_SPEED;
#endif #endif
#ifdef HAS_LCD_CONTRAST #if ENABLED(HAS_LCD_CONTRAST)
lcd_contrast = DEFAULT_LCD_CONTRAST; lcd_contrast = DEFAULT_LCD_CONTRAST;
#endif //DOGLCD #endif
#ifdef PIDTEMP #if ENABLED(PIDTEMP)
for (int8_t e = 0; e < HOTENDS; e++) { for (int8_t e = 0; e < HOTENDS; e++) {
Kp[e] = tmp6[e]; Kp[e] = tmp6[e];
Ki[e] = scalePID_i(tmp7[e]); Ki[e] = scalePID_i(tmp7[e]);
...@@ -540,13 +540,13 @@ void Config_ResetDefault() { ...@@ -540,13 +540,13 @@ void Config_ResetDefault() {
updatePID(); updatePID();
#endif // PIDTEMP #endif // PIDTEMP
#ifdef PIDTEMPBED #if ENABLED(PIDTEMPBED)
bedKp = DEFAULT_bedKp; bedKp = DEFAULT_bedKp;
bedKi = scalePID_i(DEFAULT_bedKi); bedKi = scalePID_i(DEFAULT_bedKi);
bedKd = scalePID_d(DEFAULT_bedKd); bedKd = scalePID_d(DEFAULT_bedKd);
#endif #endif
#ifdef FWRETRACT #if ENABLED(FWRETRACT)
autoretract_enabled = false; autoretract_enabled = false;
retract_length = RETRACT_LENGTH; retract_length = RETRACT_LENGTH;
#if EXTRUDERS > 1 #if EXTRUDERS > 1
...@@ -598,7 +598,7 @@ void Config_ResetDefault() { ...@@ -598,7 +598,7 @@ void Config_ResetDefault() {
} }
#endif //EXTRUDERS > 1 #endif //EXTRUDERS > 1
#ifdef SCARA #if ENABLED(SCARA)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "Scaling factors:"); ECHO_LM(DB, "Scaling factors:");
} }
...@@ -682,7 +682,7 @@ void Config_ResetDefault() { ...@@ -682,7 +682,7 @@ void Config_ResetDefault() {
} }
#endif //HOTENDS > 1 #endif //HOTENDS > 1
#ifdef DELTA #if ENABLED(DELTA)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "Delta Geometry adjustment:"); ECHO_LM(DB, "Delta Geometry adjustment:");
} }
...@@ -713,19 +713,19 @@ void Config_ResetDefault() { ...@@ -713,19 +713,19 @@ void Config_ResetDefault() {
ECHO_MV(" Y", z_probe_offset[1]); ECHO_MV(" Y", z_probe_offset[1]);
ECHO_EMV(" Z", z_probe_offset[2]); ECHO_EMV(" Z", z_probe_offset[2]);
#elif defined(Z_DUAL_ENDSTOPS) #elif ENABLED(Z_DUAL_ENDSTOPS)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "Z2 Endstop adjustement (mm):"); ECHO_LM(DB, "Z2 Endstop adjustement (mm):");
} }
ECHO_LMV(DB, " M666 Z", z_endstop_adj ); ECHO_LMV(DB, " M666 Z", z_endstop_adj );
#elif defined(ENABLE_AUTO_BED_LEVELING) #elif ENABLED(ENABLE_AUTO_BED_LEVELING)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "Z Probe offset (mm)"); ECHO_LM(DB, "Z Probe offset (mm)");
} }
ECHO_LMV(DB, " M666 P", zprobe_zoffset); ECHO_LMV(DB, " M666 P", zprobe_zoffset);
#endif #endif
#ifdef ULTIPANEL #if ENABLED(ULTIPANEL)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "Material heatup parameters:"); ECHO_LM(DB, "Material heatup parameters:");
} }
...@@ -743,7 +743,7 @@ void Config_ResetDefault() { ...@@ -743,7 +743,7 @@ void Config_ResetDefault() {
ECHO_EM(" (Material GUM)"); ECHO_EM(" (Material GUM)");
#endif // ULTIPANEL #endif // ULTIPANEL
#if defined(PIDTEMP) || defined(PIDTEMPBED) #if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "PID settings:"); ECHO_LM(DB, "PID settings:");
} }
...@@ -762,7 +762,7 @@ void Config_ResetDefault() { ...@@ -762,7 +762,7 @@ void Config_ResetDefault() {
#endif #endif
#endif #endif
#ifdef FWRETRACT #if ENABLED(FWRETRACT)
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB,"Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)"); ECHO_LM(DB,"Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)");
} }
...@@ -850,7 +850,7 @@ void ConfigSD_ResetDefault() { ...@@ -850,7 +850,7 @@ void ConfigSD_ResetDefault() {
ECHO_LM(OK, "Hardcoded SD Default Settings Loaded"); ECHO_LM(OK, "Hardcoded SD Default Settings Loaded");
} }
#if defined(SDSUPPORT) && defined(SD_SETTINGS) #if ENABLED(SDSUPPORT) && ENABLED(SD_SETTINGS)
void ConfigSD_StoreSettings() { void ConfigSD_StoreSettings() {
if(!IS_SD_INSERTED || card.isFileOpen() || card.sdprinting) return; if(!IS_SD_INSERTED || card.isFileOpen() || card.sdprinting) return;
......
...@@ -6,7 +6,7 @@ ...@@ -6,7 +6,7 @@
void Config_ResetDefault(); void Config_ResetDefault();
void ConfigSD_ResetDefault(); void ConfigSD_ResetDefault();
#ifndef DISABLE_M503 #if DISABLED(DISABLE_M503)
void Config_PrintSettings(bool forReplay = false); void Config_PrintSettings(bool forReplay = false);
void ConfigSD_PrintSettings(bool forReplay = false); void ConfigSD_PrintSettings(bool forReplay = false);
#else #else
...@@ -14,7 +14,7 @@ void ConfigSD_ResetDefault(); ...@@ -14,7 +14,7 @@ void ConfigSD_ResetDefault();
FORCE_INLINE void ConfigSD_PrintSettings(bool forReplay = false) {} FORCE_INLINE void ConfigSD_PrintSettings(bool forReplay = false) {}
#endif #endif
#ifdef EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS)
void Config_StoreSettings(); void Config_StoreSettings();
void Config_RetrieveSettings(); void Config_RetrieveSettings();
#else #else
...@@ -22,7 +22,7 @@ void ConfigSD_ResetDefault(); ...@@ -22,7 +22,7 @@ void ConfigSD_ResetDefault();
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); } FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
#endif #endif
#if defined(SDSUPPORT) && defined(SD_SETTINGS) #if ENABLED(SDSUPPORT) && ENABLED(SD_SETTINGS)
static const char *cfgSD_KEY[] = { //Keep this in lexicographical order for better search performance(O(Nlog2(N)) insted of O(N*N)) (if you don't keep this sorted, the algorithm for find the key index won't work, keep attention.) static const char *cfgSD_KEY[] = { //Keep this in lexicographical order for better search performance(O(Nlog2(N)) insted of O(N*N)) (if you don't keep this sorted, the algorithm for find the key index won't work, keep attention.)
#ifdef POWER_CONSUMPTION #ifdef POWER_CONSUMPTION
"PWR", "PWR",
......
#include "Configuration.h" #include "Configuration.h"
#ifdef DIGIPOT_I2C #if ENABLED(DIGIPOT_I2C)
#include "Stream.h" #include "Stream.h"
#include "utility/twi.h" #include "utility/twi.h"
......
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
// Please note that using the high-res version takes 402Bytes of PROGMEM. // Please note that using the high-res version takes 402Bytes of PROGMEM.
//#define START_BMPHIGH //#define START_BMPHIGH
#ifdef START_BMPHIGH #if ENABLED(START_BMPHIGH)
#define START_BMPWIDTH 112 #define START_BMPWIDTH 112
#define START_BMPHEIGHT 38 #define START_BMPHEIGHT 38
#define START_BMPBYTEWIDTH 14 #define START_BMPBYTEWIDTH 14
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
* Implementation of the LCD display routines for a DOGM128 graphic display. These are common LCD 128x64 pixel graphic displays. * Implementation of the LCD display routines for a DOGM128 graphic display. These are common LCD 128x64 pixel graphic displays.
*/ */
#ifdef ULTIPANEL #if ENABLED(ULTIPANEL)
#define BLEN_A 0 #define BLEN_A 0
#define BLEN_B 1 #define BLEN_B 1
#define BLEN_C 2 #define BLEN_C 2
...@@ -35,12 +35,12 @@ ...@@ -35,12 +35,12 @@
#include "ultralcd_st7920_u8glib_rrd.h" #include "ultralcd_st7920_u8glib_rrd.h"
#include "Configuration.h" #include "Configuration.h"
#if !defined(MAPPER_C2C3) && !defined(MAPPER_NON) && defined(USE_BIG_EDIT_FONT) #if DISABLED(MAPPER_C2C3) && DISABLED(MAPPER_NON) && ENABLED(USE_BIG_EDIT_FONT)
#undef USE_BIG_EDIT_FONT #undef USE_BIG_EDIT_FONT
#endif #endif
#ifdef USE_SMALL_INFOFONT #if ENABLED(USE_SMALL_INFOFONT)
#include "dogm_font_data_6x9_marlin.h" #include "dogm_font_data_6x9_marlin.h"
#define FONT_STATUSMENU_NAME u8g_font_6x9 #define FONT_STATUSMENU_NAME u8g_font_6x9
#else #else
...@@ -50,17 +50,17 @@ ...@@ -50,17 +50,17 @@
#include "dogm_font_data_Marlin_symbols.h" // The Marlin special symbols #include "dogm_font_data_Marlin_symbols.h" // The Marlin special symbols
#define FONT_SPECIAL_NAME Marlin_symbols #define FONT_SPECIAL_NAME Marlin_symbols
#ifndef SIMULATE_ROMFONT #if DISABLED(SIMULATE_ROMFONT)
#if defined( DISPLAY_CHARSET_ISO10646_1 ) #if ENABLED(DISPLAY_CHARSET_ISO10646_1)
#include "dogm_font_data_ISO10646_1.h" #include "dogm_font_data_ISO10646_1.h"
#define FONT_MENU_NAME ISO10646_1_5x7 #define FONT_MENU_NAME ISO10646_1_5x7
#elif defined( DISPLAY_CHARSET_ISO10646_5 ) #elif ENABLED(DISPLAY_CHARSET_ISO10646_5)
#include "dogm_font_data_ISO10646_5_Cyrillic.h" #include "dogm_font_data_ISO10646_5_Cyrillic.h"
#define FONT_MENU_NAME ISO10646_5_Cyrillic_5x7 #define FONT_MENU_NAME ISO10646_5_Cyrillic_5x7
#elif defined( DISPLAY_CHARSET_ISO10646_KANA ) #elif ENABLED(DISPLAY_CHARSET_ISO10646_KANA)
#include "dogm_font_data_ISO10646_Kana.h" #include "dogm_font_data_ISO10646_Kana.h"
#define FONT_MENU_NAME ISO10646_Kana_5x7 #define FONT_MENU_NAME ISO10646_Kana_5x7
#elif defined( DISPLAY_CHARSET_ISO10646_CN ) #elif ENABLED(DISPLAY_CHARSET_ISO10646_CN)
#include "dogm_font_data_ISO10646_CN.h" #include "dogm_font_data_ISO10646_CN.h"
#define FONT_MENU_NAME ISO10646_CN #define FONT_MENU_NAME ISO10646_CN
#define TALL_FONT_CORRECTION 1 #define TALL_FONT_CORRECTION 1
...@@ -69,13 +69,13 @@ ...@@ -69,13 +69,13 @@
#define FONT_MENU_NAME ISO10646_1_5x7 #define FONT_MENU_NAME ISO10646_1_5x7
#endif #endif
#else // SIMULATE_ROMFONT #else // SIMULATE_ROMFONT
#if defined( DISPLAY_CHARSET_HD44780_JAPAN ) #if ENABLED(DISPLAY_CHARSET_HD44780_JAPAN)
#include "dogm_font_data_HD44780_J.h" #include "dogm_font_data_HD44780_J.h"
#define FONT_MENU_NAME HD44780_J_5x7 #define FONT_MENU_NAME HD44780_J_5x7
#elif defined( DISPLAY_CHARSET_HD44780_WESTERN ) #elif ENABLED(DISPLAY_CHARSET_HD44780_WESTERN)
#include "dogm_font_data_HD44780_W.h" #include "dogm_font_data_HD44780_W.h"
#define FONT_MENU_NAME HD44780_W_5x7 #define FONT_MENU_NAME HD44780_W_5x7
#elif defined( DISPLAY_CHARSET_HD44780_CYRILLIC ) #elif ENABLED(DISPLAY_CHARSET_HD44780_CYRILLIC)
#include "dogm_font_data_HD44780_C.h" #include "dogm_font_data_HD44780_C.h"
#define FONT_MENU_NAME HD44780_C_5x7 #define FONT_MENU_NAME HD44780_C_5x7
#else // fall-back #else // fall-back
...@@ -94,7 +94,7 @@ ...@@ -94,7 +94,7 @@
// DOGM parameters (size in pixels) // DOGM parameters (size in pixels)
#define DOG_CHAR_WIDTH 6 #define DOG_CHAR_WIDTH 6
#define DOG_CHAR_HEIGHT 12 #define DOG_CHAR_HEIGHT 12
#ifdef USE_BIG_EDIT_FONT #if ENABLED(USE_BIG_EDIT_FONT)
#define FONT_MENU_EDIT_NAME u8g_font_9x18 #define FONT_MENU_EDIT_NAME u8g_font_9x18
#define DOG_CHAR_WIDTH_EDIT 9 #define DOG_CHAR_WIDTH_EDIT 9
#define DOG_CHAR_HEIGHT_EDIT 18 #define DOG_CHAR_HEIGHT_EDIT 18
...@@ -113,19 +113,19 @@ ...@@ -113,19 +113,19 @@
#define START_ROW 0 #define START_ROW 0
// LCD selection // LCD selection
#ifdef U8GLIB_ST7920 #if ENABLED(U8GLIB_ST7920)
//U8GLIB_ST7920_128X64_RRD u8g(0,0,0); //U8GLIB_ST7920_128X64_RRD u8g(0,0,0);
//U8GLIB_ST7920_128X64_RRD u8g(0); //U8GLIB_ST7920_128X64_RRD u8g(0);
U8GLIB_ST7920_128X64_1X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); U8GLIB_ST7920_128X64_1X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS);
#elif defined(U8GLIB_SSD1306) #elif defined(U8GLIB_SSD1306)
U8GLIB_SSD1306_128X64 u8g(U8G_I2C_OPT_DEV_0|U8G_I2C_OPT_NO_ACK|U8G_I2C_OPT_FAST); U8GLIB_SSD1306_128X64 u8g(U8G_I2C_OPT_DEV_0|U8G_I2C_OPT_NO_ACK|U8G_I2C_OPT_FAST);
#elif defined(MAKRPANEL) #elif ENABLED(MAKRPANEL)
// The MaKrPanel display, ST7565 controller as well // The MaKrPanel display, ST7565 controller as well
U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0); U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0);
#elif defined(VIKI2) || defined(miniVIKI) #elif ENABLED(VIKI2) || ENABLED(miniVIKI)
// Mini Viki and Viki 2.0 LCD, ST7565 controller as well // Mini Viki and Viki 2.0 LCD, ST7565 controller as well
U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0); U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0);
#elif defined(U8GLIB_LM6059_AF) #elif ENABLED(U8GLIB_LM6059_AF)
// Based on the Adafruit ST7565 (http://www.adafruit.com/products/250) // Based on the Adafruit ST7565 (http://www.adafruit.com/products/250)
U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0); U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0);
#elif defined U8GLIB_SSD1306 #elif defined U8GLIB_SSD1306
...@@ -198,12 +198,12 @@ static bool show_splashscreen = true; ...@@ -198,12 +198,12 @@ static bool show_splashscreen = true;
/* Warning: This function is called from interrupt context */ /* Warning: This function is called from interrupt context */
static void lcd_implementation_init() { static void lcd_implementation_init() {
#ifdef LCD_PIN_BL // Enable LCD backlight #if ENABLED(LCD_PIN_BL) // Enable LCD backlight
pinMode(LCD_PIN_BL, OUTPUT); pinMode(LCD_PIN_BL, OUTPUT);
digitalWrite(LCD_PIN_BL, HIGH); digitalWrite(LCD_PIN_BL, HIGH);
#endif #endif
#ifdef LCD_PIN_RESET #if ENABLED(LCD_PIN_RESET)
pinMode(LCD_PIN_RESET, OUTPUT); pinMode(LCD_PIN_RESET, OUTPUT);
digitalWrite(LCD_PIN_RESET, HIGH); digitalWrite(LCD_PIN_RESET, HIGH);
#endif #endif
...@@ -215,17 +215,17 @@ static void lcd_implementation_init() { ...@@ -215,17 +215,17 @@ static void lcd_implementation_init() {
// pinMode(17, OUTPUT); // Enable LCD backlight // pinMode(17, OUTPUT); // Enable LCD backlight
// digitalWrite(17, HIGH); // digitalWrite(17, HIGH);
#ifdef LCD_SCREEN_ROT_90 #if ENABLED(LCD_SCREEN_ROT_90)
u8g.setRot90(); // Rotate screen by 90° u8g.setRot90(); // Rotate screen by 90°
#elif defined(LCD_SCREEN_ROT_180) #elif ENABLED(LCD_SCREEN_ROT_180)
u8g.setRot180(); // Rotate screen by 180° u8g.setRot180(); // Rotate screen by 180°
#elif defined(LCD_SCREEN_ROT_270) #elif ENABLED(LCD_SCREEN_ROT_270)
u8g.setRot270(); // Rotate screen by 270° u8g.setRot270(); // Rotate screen by 270°
#endif #endif
// Show splashscreen // Show splashscreen
int offx = (u8g.getWidth() - START_BMPWIDTH) / 2; int offx = (u8g.getWidth() - START_BMPWIDTH) / 2;
#ifdef START_BMPHIGH #if ENABLED(START_BMPHIGH)
int offy = 0; int offy = 0;
#else #else
int offy = DOG_CHAR_HEIGHT; int offy = DOG_CHAR_HEIGHT;
...@@ -239,7 +239,7 @@ static void lcd_implementation_init() { ...@@ -239,7 +239,7 @@ static void lcd_implementation_init() {
u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp); u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp);
lcd_setFont(FONT_MENU); lcd_setFont(FONT_MENU);
#ifndef STRING_SPLASH_LINE2 #ifndef STRING_SPLASH_LINE2
u8g.drawStr(0, u8g.getHeight(), STRING_SPLASH_LINE1); u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT, STRING_SPLASH_LINE1);
#else #else
int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1)*DOG_CHAR_WIDTH) / 2; int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1)*DOG_CHAR_WIDTH) / 2;
u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT*3/2, STRING_SPLASH_LINE1); u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT*3/2, STRING_SPLASH_LINE1);
...@@ -280,7 +280,7 @@ static void lcd_implementation_status_screen() { ...@@ -280,7 +280,7 @@ static void lcd_implementation_status_screen() {
// Symbols menu graphics, animated fan // Symbols menu graphics, animated fan
u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp); u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp);
#ifdef SDSUPPORT #if ENABLED(SDSUPPORT)
// SD Card Symbol // SD Card Symbol
u8g.drawBox(42, 42 - TALL_FONT_CORRECTION, 8, 7); u8g.drawBox(42, 42 - TALL_FONT_CORRECTION, 8, 7);
u8g.drawBox(50, 44 - TALL_FONT_CORRECTION, 2, 5); u8g.drawBox(50, 44 - TALL_FONT_CORRECTION, 2, 5);
...@@ -348,7 +348,7 @@ static void lcd_implementation_status_screen() { ...@@ -348,7 +348,7 @@ static void lcd_implementation_status_screen() {
#define XYZ_BASELINE 38 #define XYZ_BASELINE 38
lcd_setFont(FONT_STATUSMENU); lcd_setFont(FONT_STATUSMENU);
#ifdef USE_SMALL_INFOFONT #if ENABLED(USE_SMALL_INFOFONT)
u8g.drawBox(0,30,LCD_PIXEL_WIDTH,10); u8g.drawBox(0,30,LCD_PIXEL_WIDTH,10);
#else #else
u8g.drawBox(0,30,LCD_PIXEL_WIDTH,9); u8g.drawBox(0,30,LCD_PIXEL_WIDTH,9);
...@@ -394,7 +394,7 @@ static void lcd_implementation_status_screen() { ...@@ -394,7 +394,7 @@ static void lcd_implementation_status_screen() {
// Status line // Status line
lcd_setFont(FONT_STATUSMENU); lcd_setFont(FONT_STATUSMENU);
#ifdef USE_SMALL_INFOFONT #if ENABLED(USE_SMALL_INFOFONT)
u8g.setPrintPos(0,62); u8g.setPrintPos(0,62);
#else #else
u8g.setPrintPos(0,63); u8g.setPrintPos(0,63);
...@@ -506,7 +506,7 @@ void lcd_implementation_drawedit(const char* pstr, char* value) { ...@@ -506,7 +506,7 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
uint8_t lcd_width = LCD_WIDTH, char_width = DOG_CHAR_WIDTH; uint8_t lcd_width = LCD_WIDTH, char_width = DOG_CHAR_WIDTH;
uint8_t vallen = lcd_strlen(value); uint8_t vallen = lcd_strlen(value);
#ifdef USE_BIG_EDIT_FONT #if ENABLED(USE_BIG_EDIT_FONT)
if (lcd_strlen_P(pstr) <= LCD_WIDTH_EDIT - 1) { if (lcd_strlen_P(pstr) <= LCD_WIDTH_EDIT - 1) {
lcd_setFont(FONT_MENU_EDIT); lcd_setFont(FONT_MENU_EDIT);
lcd_width = LCD_WIDTH_EDIT + 1; lcd_width = LCD_WIDTH_EDIT + 1;
......
...@@ -3,4 +3,24 @@ In Fony export the fonts to bdf-format. Maybe another one can edit them with Fon ...@@ -3,4 +3,24 @@ In Fony export the fonts to bdf-format. Maybe another one can edit them with Fon
Then run make_fonts.bat what calls bdf2u8g.exe with the needed parameters to produce the .h files. Then run make_fonts.bat what calls bdf2u8g.exe with the needed parameters to produce the .h files.
The .h files must be edited to replace '#include "u8g.h"' with '#include <utility/u8g.h>', replace 'U8G_FONT_SECTION' with 'U8G_SECTION', insert '.progmem.' right behind the first '"' and moved to the main directory. The .h files must be edited to replace '#include "u8g.h"' with '#include <utility/u8g.h>', replace 'U8G_FONT_SECTION' with 'U8G_SECTION', insert '.progmem.' right behind the first '"' and moved to the main directory.
Especially the Kana and Cyrillic fonts should be revised by someone who knows what he/she does. I am only a west-European with very little knowledge about this scripts. How to integrate a new font:
Currently we are limited to 256 symbols per font. We use a menu system with 5 lines, on a display with 64 pixel height. That means we have 12 pixel for a line. To have some space in between the lines we can't use more then 10 pixel height for the symbols. For up to 11 pixel set TALL_FONT_CORRECTION 1 when loading the font.
To fit 22 Symbols on the 128 pixel wide screen, the symbols can't be wider than 5 pixel, for the first 128 symbols.
For the second half of the font we now support up to 11x11 pixel.
* Get 'Fony.exe'
* Copy one of the existing *.fon files and work with this.
* Change the pixels. Don't change width or height.
* Export as *.bdf
* Use 'bdf2u8g.exe' to produce the *.h file. Examples for the existing fonts are in 'make_fonts.bat'
* Edit the produced .h file to match our needs. See hints in 'README.fonts' or the other 'dogm_font_data_.h' files.
* Make a new entry in the font list in 'dogm_lcd_implementation.h' before the '#else // fall back'
#elif ENABLED(DISPLAY_CHARSET_NEWNAME)
#include "dogm_font_data_yourfont.h"
#define FONT_MENU_NAME YOURFONTNAME
#else // fall-back
* Add your font to the list of permitted fonts in 'language_en.h'
... || ENABLED(DISPLAY_CHARSET_YOUR_NEW_FONT) ... )
Especially the Kana font should be revised by someone who knows what he/she does. I am only a west-European with very little knowledge about this script.
...@@ -3,6 +3,6 @@ ...@@ -3,6 +3,6 @@
.\bdf2u8g.exe -b 32 -e 255 HD44780_C.bdf HD44780_C_5x7 dogm_font_data_HD44780_C.h .\bdf2u8g.exe -b 32 -e 255 HD44780_C.bdf HD44780_C_5x7 dogm_font_data_HD44780_C.h
.\bdf2u8g.exe -b 32 -e 255 HD44780_J.bdf HD44780_J_5x7 dogm_font_data_HD44780_J.h .\bdf2u8g.exe -b 32 -e 255 HD44780_J.bdf HD44780_J_5x7 dogm_font_data_HD44780_J.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646-1.bdf ISO10646_1_5x7 dogm_font_data_ISO10646_1.h .\bdf2u8g.exe -b 32 -e 255 ISO10646-1.bdf ISO10646_1_5x7 dogm_font_data_ISO10646_1.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646-1-Marlin.bdf ISO10646_1_Marlin_5x7 dogm_font_data_ISO10646_1_Marlin.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646_5_Cyrillic.bdf ISO10646_5_Cyrillic_5x7 dogm_font_data_ISO10646_5_Cyrillic.h .\bdf2u8g.exe -b 32 -e 255 ISO10646_5_Cyrillic.bdf ISO10646_5_Cyrillic_5x7 dogm_font_data_ISO10646_5_Cyrillic.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646_Kana.bdf ISO10646_Kana_5x7 dogm_font_data_ISO10646_Kana.h .\bdf2u8g.exe -b 32 -e 255 ISO10646_Kana.bdf ISO10646_Kana_5x7 dogm_font_data_ISO10646_Kana.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646_CN.bdf ISO10646_CN dogm_font_data_ISO10646_CN.h
...@@ -109,10 +109,11 @@ ...@@ -109,10 +109,11 @@
#define MSG_INVALID_EXTRUDER "Invalid extruder" #define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid" #define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature" #define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
#define MSG_M115_REPORT "FIRMWARE_NAME: MarlinKimbra " BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n" #define MSG_M115_REPORT "FIRMWARE_NAME:MarlinKimbra " BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
#define MSG_COUNT_X " Count X: " #define MSG_COUNT_X " Count X: "
#define MSG_ERR_KILLED "Printer halted. kill() called!" #define MSG_ERR_KILLED "Printer halted. kill() called!"
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)" #define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
#define MSG_RESEND "Resend: "
#define MSG_UNKNOWN_COMMAND "Unknown command: \"" #define MSG_UNKNOWN_COMMAND "Unknown command: \""
#define MSG_ACTIVE_DRIVER "Active Driver: " #define MSG_ACTIVE_DRIVER "Active Driver: "
#define MSG_ACTIVE_EXTRUDER "Active Extruder: " #define MSG_ACTIVE_EXTRUDER "Active Extruder: "
......
This diff is collapsed.
...@@ -50,6 +50,7 @@ ...@@ -50,6 +50,7 @@
// #undef X_MIN_PIN // #undef X_MIN_PIN
// #define X_MIN_PIN newpin // #define X_MIN_PIN newpin
#undef Z_PROBE_PIN
#define Z_PROBE_PIN 18
//============================================================================ //============================================================================
This diff is collapsed.
...@@ -37,7 +37,7 @@ typedef struct { ...@@ -37,7 +37,7 @@ typedef struct {
long acceleration_rate; // The acceleration rate used for acceleration calculation long acceleration_rate; // The acceleration rate used for acceleration calculation
unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
unsigned char active_driver; // Selects the active driver unsigned char active_driver; // Selects the active driver
#ifdef ADVANCE #if ENABLED(ADVANCE)
long advance_rate; long advance_rate;
volatile long initial_advance; volatile long initial_advance;
volatile long final_advance; volatile long final_advance;
...@@ -60,11 +60,11 @@ typedef struct { ...@@ -60,11 +60,11 @@ typedef struct {
unsigned long final_rate; // The minimal rate at exit unsigned long final_rate; // The minimal rate at exit
unsigned long acceleration_st; // acceleration steps/sec^2 unsigned long acceleration_st; // acceleration steps/sec^2
unsigned long fan_speed; unsigned long fan_speed;
#ifdef BARICUDA #if ENABLED(BARICUDA)
unsigned long valve_pressure; unsigned long valve_pressure;
unsigned long e_to_p_pressure; unsigned long e_to_p_pressure;
#endif #endif
#ifdef LASERBEAM #if ENABLED(LASERBEAM)
unsigned long laser_ttlmodulation; unsigned long laser_ttlmodulation;
#endif #endif
volatile char busy; volatile char busy;
...@@ -82,7 +82,7 @@ extern volatile unsigned char block_buffer_head; ...@@ -82,7 +82,7 @@ extern volatile unsigned char block_buffer_head;
extern volatile unsigned char block_buffer_tail; extern volatile unsigned char block_buffer_tail;
FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_tail + BLOCK_BUFFER_SIZE); } FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_tail + BLOCK_BUFFER_SIZE); }
#ifdef ENABLE_AUTO_BED_LEVELING #if ENABLED(ENABLE_AUTO_BED_LEVELING)
#include "vector_3.h" #include "vector_3.h"
...@@ -132,7 +132,7 @@ extern float max_e_jerk[EXTRUDERS]; // mm/s - initial speed for extruder retract ...@@ -132,7 +132,7 @@ extern float max_e_jerk[EXTRUDERS]; // mm/s - initial speed for extruder retract
extern float mintravelfeedrate; extern float mintravelfeedrate;
extern unsigned long axis_steps_per_sqr_second[3 + EXTRUDERS]; extern unsigned long axis_steps_per_sqr_second[3 + EXTRUDERS];
#ifdef AUTOTEMP #if ENABLED(AUTOTEMP)
extern bool autotemp_enabled; extern bool autotemp_enabled;
extern float autotemp_max; extern float autotemp_max;
extern float autotemp_min; extern float autotemp_min;
......
#include "qr_solve.h" #include "qr_solve.h"
#ifdef AUTO_BED_LEVELING_GRID #if ENABLED(AUTO_BED_LEVELING_GRID)
#include <stdlib.h> #include <stdlib.h>
#include <math.h> #include <math.h>
...@@ -260,7 +260,7 @@ double r8mat_amax ( int m, int n, double a[] ) ...@@ -260,7 +260,7 @@ double r8mat_amax ( int m, int n, double a[] )
return value; return value;
} }
double *r8mat_copy_new ( int m, int n, double a1[] ) void r8mat_copy( double a2[], int m, int n, double a1[] )
/******************************************************************************/ /******************************************************************************/
/* /*
...@@ -294,12 +294,9 @@ double *r8mat_copy_new ( int m, int n, double a1[] ) ...@@ -294,12 +294,9 @@ double *r8mat_copy_new ( int m, int n, double a1[] )
Output, double R8MAT_COPY_NEW[M*N], the copy of A1. Output, double R8MAT_COPY_NEW[M*N], the copy of A1.
*/ */
{ {
double *a2;
int i; int i;
int j; int j;
a2 = ( double * ) malloc ( m * n * sizeof ( double ) );
for ( j = 0; j < n; j++ ) for ( j = 0; j < n; j++ )
{ {
for ( i = 0; i < m; i++ ) for ( i = 0; i < m; i++ )
...@@ -307,8 +304,6 @@ double *r8mat_copy_new ( int m, int n, double a1[] ) ...@@ -307,8 +304,6 @@ double *r8mat_copy_new ( int m, int n, double a1[] )
a2[i+j*m] = a1[i+j*m]; a2[i+j*m] = a1[i+j*m];
} }
} }
return a2;
} }
/******************************************************************************/ /******************************************************************************/
...@@ -726,14 +721,13 @@ void dqrank ( double a[], int lda, int m, int n, double tol, int *kr, ...@@ -726,14 +721,13 @@ void dqrank ( double a[], int lda, int m, int n, double tol, int *kr,
int j; int j;
int job; int job;
int k; int k;
double *work; double work[n];
for ( i = 0; i < n; i++ ) for ( i = 0; i < n; i++ )
{ {
jpvt[i] = 0; jpvt[i] = 0;
} }
work = ( double * ) malloc ( n * sizeof ( double ) );
job = 1; job = 1;
dqrdc ( a, lda, m, n, qraux, jpvt, work, job ); dqrdc ( a, lda, m, n, qraux, jpvt, work, job );
...@@ -750,8 +744,6 @@ void dqrank ( double a[], int lda, int m, int n, double tol, int *kr, ...@@ -750,8 +744,6 @@ void dqrank ( double a[], int lda, int m, int n, double tol, int *kr,
*kr = j + 1; *kr = j + 1;
} }
free ( work );
return; return;
} }
/******************************************************************************/ /******************************************************************************/
...@@ -1845,7 +1837,7 @@ void dswap ( int n, double x[], int incx, double y[], int incy ) ...@@ -1845,7 +1837,7 @@ void dswap ( int n, double x[], int incx, double y[], int incy )
/******************************************************************************/ /******************************************************************************/
double *qr_solve ( int m, int n, double a[], double b[] ) void qr_solve ( double x[], int m, int n, double a[], double b[] )
/******************************************************************************/ /******************************************************************************/
/* /*
...@@ -1895,34 +1887,22 @@ double *qr_solve ( int m, int n, double a[], double b[] ) ...@@ -1895,34 +1887,22 @@ double *qr_solve ( int m, int n, double a[], double b[] )
Output, double QR_SOLVE[N], the least squares solution. Output, double QR_SOLVE[N], the least squares solution.
*/ */
{ {
double *a_qr; double a_qr[n*m];
int ind; int ind;
int itask; int itask;
int *jpvt; int jpvt[n];
int kr; int kr;
int lda; int lda;
double *qraux; double qraux[n];
double *r; double r[m];
double tol; double tol;
double *x;
a_qr = r8mat_copy_new ( m, n, a ); r8mat_copy( a_qr, m, n, a );
lda = m; lda = m;
tol = r8_epsilon ( ) / r8mat_amax ( m, n, a_qr ); tol = r8_epsilon ( ) / r8mat_amax ( m, n, a_qr );
x = ( double * ) malloc ( n * sizeof ( double ) );
jpvt = ( int * ) malloc ( n * sizeof ( int ) );
qraux = ( double * ) malloc ( n * sizeof ( double ) );
r = ( double * ) malloc ( m * sizeof ( double ) );
itask = 1; itask = 1;
ind = dqrls ( a_qr, lda, m, n, tol, &kr, b, x, r, jpvt, qraux, itask ); ind = dqrls ( a_qr, lda, m, n, tol, &kr, b, x, r, jpvt, qraux, itask );
free ( a_qr );
free ( jpvt );
free ( qraux );
free ( r );
return x;
} }
/******************************************************************************/ /******************************************************************************/
......
#include "Configuration.h" #include "Configuration.h"
#ifdef AUTO_BED_LEVELING_GRID #if ENABLED(AUTO_BED_LEVELING_GRID)
void daxpy ( int n, double da, double dx[], int incx, double dy[], int incy ); void daxpy ( int n, double da, double dx[], int incx, double dy[], int incy );
double ddot ( int n, double dx[], int incx, double dy[], int incy ); double ddot ( int n, double dx[], int incx, double dy[], int incy );
...@@ -17,6 +17,6 @@ int dqrsl ( double a[], int lda, int n, int k, double qraux[], double y[], ...@@ -17,6 +17,6 @@ int dqrsl ( double a[], int lda, int n, int k, double qraux[], double y[],
double qy[], double qty[], double b[], double rsd[], double ab[], int job ); double qy[], double qty[], double b[], double rsd[], double ab[], int job );
void dscal ( int n, double sa, double x[], int incx ); void dscal ( int n, double sa, double x[], int incx );
void dswap ( int n, double x[], int incx, double y[], int incy ); void dswap ( int n, double x[], int incx, double y[], int incy );
double *qr_solve ( int m, int n, double a[], double b[] ); void qr_solve ( double x[], int m, int n, double a[], double b[] );
#endif #endif
...@@ -9,24 +9,24 @@ ...@@ -9,24 +9,24 @@
/** /**
* Dual Stepper Drivers * Dual Stepper Drivers
*/ */
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Y_DUAL_STEPPER_DRIVERS) #if ENABLED(Z_DUAL_STEPPER_DRIVERS) && ENABLED(Y_DUAL_STEPPER_DRIVERS)
#error You cannot have dual stepper drivers for both Y and Z. #error You cannot have dual stepper drivers for both Y and Z.
#endif #endif
/** /**
* Progress Bar * Progress Bar
*/ */
#ifdef LCD_PROGRESS_BAR #if ENABLED(LCD_PROGRESS_BAR)
#ifndef SDSUPPORT #if DISABLED(SDSUPPORT)
#error LCD_PROGRESS_BAR requires SDSUPPORT. #error LCD_PROGRESS_BAR requires SDSUPPORT.
#endif #endif
#ifdef DOGLCD #if ENABLED(DOGLCD)
#error LCD_PROGRESS_BAR does not apply to graphical displays. #error LCD_PROGRESS_BAR does not apply to graphical displays.
#endif #endif
#ifdef FILAMENT_LCD_DISPLAY #if ENABLED(FILAMENT_LCD_DISPLAY)
#error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both. #error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
#endif #endif
#ifdef POWER_CONSUMPTION_LCD_DISPLAY #if ENABLED(POWER_CONSUMPTION_LCD_DISPLAY)
#error LCD_PROGRESS_BAR and POWER_CONSUMPTION_LCD_DISPLAY are not fully compatible. Comment out this line to use both. #error LCD_PROGRESS_BAR and POWER_CONSUMPTION_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
#endif #endif
#endif #endif
...@@ -34,14 +34,14 @@ ...@@ -34,14 +34,14 @@
/** /**
* Babystepping * Babystepping
*/ */
#ifdef BABYSTEPPING #if ENABLED(BABYSTEPPING)
#ifdef COREXY #if ENABLED(COREXY) && ENABLED(BABYSTEP_XY)
#error BABYSTEPPING not implemented for COREXY yet. #error BABYSTEPPING only implemented for Z axis on CoreXY.
#endif #endif
#ifdef SCARA #if ENABLED(SCARA)
#error BABYSTEPPING is not implemented for SCARA yet. #error BABYSTEPPING is not implemented for SCARA yet.
#endif #endif
#if defined(DELTA) && defined(BABYSTEP_XY) #if ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
#error BABYSTEPPING only implemented for Z axis on deltabots. #error BABYSTEPPING only implemented for Z axis on deltabots.
#endif #endif
#endif #endif
...@@ -49,28 +49,28 @@ ...@@ -49,28 +49,28 @@
/** /**
* Filament Change with Extruder Runout Prevention * Filament Change with Extruder Runout Prevention
*/ */
#if defined(FILAMENTCHANGEENABLE) && defined(EXTRUDER_RUNOUT_PREVENT) #if ENABLED(FILAMENTCHANGEENABLE) && ENABLED(EXTRUDER_RUNOUT_PREVENT)
#error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE. #error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE.
#endif #endif
/** /**
* Extruder Runout Prevention * Extruder Runout Prevention
*/ */
#if defined(EXTRUDER_RUNOUT_PREVENT) && EXTRUDER_RUNOUT_MINTEMP < EXTRUDE_MINTEMP #if ENABLED(EXTRUDER_RUNOUT_PREVENT) && EXTRUDER_RUNOUT_MINTEMP < EXTRUDE_MINTEMP
#error EXTRUDER_RUNOUT_MINTEMP have to be greater than EXTRUDE_MINTEMP #error EXTRUDER_RUNOUT_MINTEMP have to be greater than EXTRUDE_MINTEMP
#endif #endif
/** /**
* Idle oozing prevent with Extruder Runout Prevention * Idle oozing prevent with Extruder Runout Prevention
*/ */
#if defined(EXTRUDER_RUNOUT_PREVENT) && defined(IDLE_OOZING_PREVENT) #if ENABLED(EXTRUDER_RUNOUT_PREVENT) && ENABLED(IDLE_OOZING_PREVENT)
#error EXTRUDER_RUNOUT_PREVENT and IDLE_OOZING_PREVENT are incopatible. Please comment one of them. #error EXTRUDER_RUNOUT_PREVENT and IDLE_OOZING_PREVENT are incopatible. Please comment one of them.
#endif #endif
/** /**
* Idle oozing prevent * Idle oozing prevent
*/ */
#if defined(IDLE_OOZING_PREVENT) && IDLE_OOZING_MINTEMP < EXTRUDE_MINTEMP #if ENABLED(IDLE_OOZING_PREVENT) && IDLE_OOZING_MINTEMP < EXTRUDE_MINTEMP
#error IDLE_OOZING_MINTEMP have to be greater than EXTRUDE_MINTEMP #error IDLE_OOZING_MINTEMP have to be greater than EXTRUDE_MINTEMP
#endif #endif
...@@ -79,22 +79,14 @@ ...@@ -79,22 +79,14 @@
*/ */
#if EXTRUDERS > 1 #if EXTRUDERS > 1
#ifdef TEMP_SENSOR_1_AS_REDUNDANT #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
#error EXTRUDERS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT. #error EXTRUDERS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT.
#endif #endif
#ifdef HEATERS_PARALLEL #if ENABLED(HEATERS_PARALLEL)
#error EXTRUDERS must be 1 with HEATERS_PARALLEL. #error EXTRUDERS must be 1 with HEATERS_PARALLEL.
#endif #endif
#ifdef Y_DUAL_STEPPER_DRIVERS
#error EXTRUDERS must be 1 with Y_DUAL_STEPPER_DRIVERS.
#endif
#ifdef Z_DUAL_STEPPER_DRIVERS
#error EXTRUDERS must be 1 with Z_DUAL_STEPPER_DRIVERS.
#endif
#endif // EXTRUDERS > 1 #endif // EXTRUDERS > 1
/** /**
...@@ -103,25 +95,43 @@ ...@@ -103,25 +95,43 @@
#if NUM_SERVOS > 4 #if NUM_SERVOS > 4
#error The maximum number of SERVOS in Marlin is 4. #error The maximum number of SERVOS in Marlin is 4.
#endif #endif
#if defined(NUM_SERVOS) && NUM_SERVOS > 0
#if X_ENDSTOP_SERVO_NR >= 0 || Y_ENDSTOP_SERVO_NR >= 0 || Z_ENDSTOP_SERVO_NR >= 0
#if X_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error X_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#elif Y_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error Y_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#elif Z_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error Z_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#endif
#endif
#endif
/**
* Servo deactivation depends on servo endstops
*/
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_SERVO_ENDSTOPS
#error At least one of the ?_ENDSTOP_SERVO_NR is required for DEACTIVATE_SERVOS_AFTER_MOVE.
#endif
/** /**
* Required LCD language * Required LCD language
*/ */
#if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)&& !defined(DISPLAY_CHARSET_HD44780_CYRILLIC) #if DISABLED(DOGLCD) && ENABLED(ULTRA_LCD) && DISABLED(DISPLAY_CHARSET_HD44780_JAPAN) && DISABLED(DISPLAY_CHARSET_HD44780_WESTERN) && DISABLED(DISPLAY_CHARSET_HD44780_CYRILLIC)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller. #error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
#endif #endif
/** /**
* Auto Bed Leveling * Auto Bed Leveling
*/ */
#ifdef ENABLE_AUTO_BED_LEVELING #if ENABLED(ENABLE_AUTO_BED_LEVELING)
/** /**
* Require a Z Min pin * Require a Z Min pin
*/ */
#if Z_MIN_PIN == -1 #if Z_MIN_PIN == -1
#if Z_PROBE_PIN == -1 || defined(Z_PROBE_ENDSTOP) // It's possible for someone to set a pin for the Z Probe, but not enable it. #if Z_PROBE_PIN == -1 || DISABLED(Z_PROBE_ENDSTOP) // It's possible for someone to set a pin for the Z Probe, but not enable it.
#ifdef Z_PROBE_REPEATABILITY_TEST #if ENABLED(Z_PROBE_REPEATABILITY_TEST)
#error You must have a Z_MIN or Z_PROBE endstop to enable Z_PROBE_REPEATABILITY_TEST. #error You must have a Z_MIN or Z_PROBE endstop to enable Z_PROBE_REPEATABILITY_TEST.
#else #else
#error ENABLE_AUTO_BED_LEVELING requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_PROBE_PIN must point to a valid hardware pin. #error ENABLE_AUTO_BED_LEVELING requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_PROBE_PIN must point to a valid hardware pin.
...@@ -132,7 +142,7 @@ ...@@ -132,7 +142,7 @@
/** /**
* Require a Z Probe Pin if Z_PROBE_ENDSTOP is enabled. * Require a Z Probe Pin if Z_PROBE_ENDSTOP is enabled.
*/ */
#if defined(Z_PROBE_ENDSTOP) #if ENABLED(Z_PROBE_ENDSTOP)
#ifndef Z_PROBE_PIN #ifndef Z_PROBE_PIN
#error You must have a Z_PROBE_PIN defined in pins2tool.h file if you enable Z_PROBE_ENDSTOP. #error You must have a Z_PROBE_PIN defined in pins2tool.h file if you enable Z_PROBE_ENDSTOP.
#endif #endif
...@@ -141,22 +151,22 @@ ...@@ -141,22 +151,22 @@
#endif #endif
// Forcing Servo definitions can break some hall effect sensor setups. Leaving these here for further comment. // Forcing Servo definitions can break some hall effect sensor setups. Leaving these here for further comment.
// #ifndef NUM_SERVOS // #ifndef NUM_SERVOS
// #error You must have NUM_SERVOS defined and there must be at least 1 configured to use Z_PROBE_ENDSTOP // #error You must have NUM_SERVOS defined and there must be at least 1 configured to use Z_PROBE_ENDSTOP.
// #endif // #endif
// #if defined(NUM_SERVOS) && NUM_SERVOS < 1 // #if defined(NUM_SERVOS) && NUM_SERVOS < 1
// #error You must have at least 1 servo defined for NUM_SERVOS to use Z_PROBE_ENDSTOP // #error You must have at least 1 servo defined for NUM_SERVOS to use Z_PROBE_ENDSTOP.
// #endif // #endif
// #ifndef SERVO_ENDSTOPS // #if Z_ENDSTOP_SERVO_NR < 0
// #error You must have SERVO_ENDSTOPS defined and have the Z index set to at least 0 or above to use Z_PROBE_ENDSTOP // #error You must have Z_ENDSTOP_SERVO_NR set to at least 0 or above to use Z_PROBE_ENDSTOP.
// #endif // #endif
// #ifndef SERVO_ENDSTOP_ANGLES // #ifndef SERVO_ENDSTOP_ANGLES
// #error You must have SERVO_ENDSTOP_ANGLES defined for Z Extend and Retract to use Z_PROBE_AND_ENSTOP // #error You must have SERVO_ENDSTOP_ANGLES defined for Z Extend and Retract to use Z_PROBE_ENDSTOP.
// #endif // #endif
#endif #endif
/** /**
* Check if Probe_Offset * Grid Points is greater than Probing Range * Check if Probe_Offset * Grid Points is greater than Probing Range
*/ */
#ifdef AUTO_BED_LEVELING_GRID #if ENABLED(AUTO_BED_LEVELING_GRID)
// Be sure points are in the right order // Be sure points are in the right order
#if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION #if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION
#error LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION. #error LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION.
...@@ -198,14 +208,14 @@ ...@@ -198,14 +208,14 @@
/** /**
* ULTIPANEL encoder * ULTIPANEL encoder
*/ */
#if defined(ULTIPANEL) && !defined(NEWPANEL) && !defined(SR_LCD_2W_NL) && !defined(SHIFT_CLK) #if ENABLED(ULTIPANEL) && DISABLED(NEWPANEL) && DISABLED(SR_LCD_2W_NL) && !defined(SHIFT_CLK)
#error ULTIPANEL requires some kind of encoder. #error ULTIPANEL requires some kind of encoder.
#endif #endif
/** /**
* Delta & Z_PROBE_ENDSTOP * Delta & Z_PROBE_ENDSTOP
*/ */
#if defined(DELTA) && defined(Z_PROBE_ENDSTOP) #if ENABLED(DELTA) && ENABLED(Z_PROBE_ENDSTOP)
#ifndef Z_PROBE_PIN #ifndef Z_PROBE_PIN
#error You must have a Z_PROBE_PIN defined in your pins2tool.h file if you enable Z_PROBE_ENDSTOP #error You must have a Z_PROBE_PIN defined in your pins2tool.h file if you enable Z_PROBE_ENDSTOP
#endif #endif
...@@ -217,8 +227,8 @@ ...@@ -217,8 +227,8 @@
/** /**
* Dual X Carriage requirements * Dual X Carriage requirements
*/ */
#ifdef DUAL_X_CARRIAGE #if ENABLED(DUAL_X_CARRIAGE)
#if EXTRUDERS == 1 || defined(COREXY) \ #if EXTRUDERS == 1 || ENABLED(COREXY) \
|| !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR \ || !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR \
|| !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \ || !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
|| !HAS_X_MAX || !HAS_X_MAX
...@@ -280,11 +290,11 @@ ...@@ -280,11 +290,11 @@
#error WATCH_TEMP_PERIOD now uses seconds instead of milliseconds. #error WATCH_TEMP_PERIOD now uses seconds instead of milliseconds.
#endif #endif
#if !defined(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD)) #if DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD))
#error Thermal Runaway Protection for hotends must now be enabled with THERMAL_PROTECTION_HOTENDS. #error Thermal Runaway Protection for hotends must now be enabled with THERMAL_PROTECTION_HOTENDS.
#endif #endif
#if !defined(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD) #if DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD)
#error Thermal Runaway Protection for the bed must now be enabled with THERMAL_PROTECTION_BED. #error Thermal Runaway Protection for the bed must now be enabled with THERMAL_PROTECTION_BED.
#endif #endif
...@@ -296,4 +306,16 @@ ...@@ -296,4 +306,16 @@
#error "Z_LATE_ENABLE can't be used with COREXZ." #error "Z_LATE_ENABLE can't be used with COREXZ."
#endif #endif
#ifdef BEEPER
#error BEEPER has been replaced with BEEPER_PIN. Please update your pins definitions.
#endif
#ifdef SDCARDDETECT
#error SDCARDDETECT is now SD_DETECT_PIN. Please update your pins definitions.
#endif
#ifdef SDCARDDETECTINVERTED
#error SDCARDDETECTINVERTED is now SD_DETECT_INVERTED. Please update your configuration.
#endif
#endif //SANITYCHECK_H #endif //SANITYCHECK_H
...@@ -42,10 +42,10 @@ ...@@ -42,10 +42,10 @@
attached() - Returns true if there is a servo attached. attached() - Returns true if there is a servo attached.
detach() - Stops an attached servos from pulsing its i/o pin. detach() - Stops an attached servos from pulsing its i/o pin.
*/ */
#include "Configuration.h" #include "Configuration.h"
#if NUM_SERVOS > 0 #if HAS_SERVOS
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include <Arduino.h> #include <Arduino.h>
...@@ -81,14 +81,14 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t ...@@ -81,14 +81,14 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else { else {
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive) if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive)
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
} }
Channel[timer]++; // increment to the next channel Channel[timer]++; // increment to the next channel
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks; *OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
} }
else { else {
// finished all channels so wait for the refresh period to expire before starting over // finished all channels so wait for the refresh period to expire before starting over
...@@ -103,29 +103,29 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t ...@@ -103,29 +103,29 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform #ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
// Interrupt handlers for Arduino // Interrupt handlers for Arduino
#ifdef _useTimer1 #if ENABLED(_useTimer1)
SIGNAL (TIMER1_COMPA_vect) { handle_interrupts(_timer1, &TCNT1, &OCR1A); } SIGNAL (TIMER1_COMPA_vect) { handle_interrupts(_timer1, &TCNT1, &OCR1A); }
#endif #endif
#ifdef _useTimer3 #if ENABLED(_useTimer3)
SIGNAL (TIMER3_COMPA_vect) { handle_interrupts(_timer3, &TCNT3, &OCR3A); } SIGNAL (TIMER3_COMPA_vect) { handle_interrupts(_timer3, &TCNT3, &OCR3A); }
#endif #endif
#ifdef _useTimer4 #if ENABLED(_useTimer4)
SIGNAL (TIMER4_COMPA_vect) { handle_interrupts(_timer4, &TCNT4, &OCR4A); } SIGNAL (TIMER4_COMPA_vect) { handle_interrupts(_timer4, &TCNT4, &OCR4A); }
#endif #endif
#ifdef _useTimer5 #if ENABLED(_useTimer5)
SIGNAL (TIMER5_COMPA_vect) { handle_interrupts(_timer5, &TCNT5, &OCR5A); } SIGNAL (TIMER5_COMPA_vect) { handle_interrupts(_timer5, &TCNT5, &OCR5A); }
#endif #endif
#else //!WIRING #else //!WIRING
// Interrupt handlers for Wiring // Interrupt handlers for Wiring
#ifdef _useTimer1 #if ENABLED(_useTimer1)
void Timer1Service() { handle_interrupts(_timer1, &TCNT1, &OCR1A); } void Timer1Service() { handle_interrupts(_timer1, &TCNT1, &OCR1A); }
#endif #endif
#ifdef _useTimer3 #if ENABLED(_useTimer3)
void Timer3Service() { handle_interrupts(_timer3, &TCNT3, &OCR3A); } void Timer3Service() { handle_interrupts(_timer3, &TCNT3, &OCR3A); }
#endif #endif
...@@ -133,7 +133,7 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t ...@@ -133,7 +133,7 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
static void initISR(timer16_Sequence_t timer) { static void initISR(timer16_Sequence_t timer) {
#ifdef _useTimer1 #if ENABLED(_useTimer1)
if (timer == _timer1) { if (timer == _timer1) {
TCCR1A = 0; // normal counting mode TCCR1A = 0; // normal counting mode
TCCR1B = _BV(CS11); // set prescaler of 8 TCCR1B = _BV(CS11); // set prescaler of 8
...@@ -152,7 +152,7 @@ static void initISR(timer16_Sequence_t timer) { ...@@ -152,7 +152,7 @@ static void initISR(timer16_Sequence_t timer) {
} }
#endif #endif
#ifdef _useTimer3 #if ENABLED(_useTimer3)
if (timer == _timer3) { if (timer == _timer3) {
TCCR3A = 0; // normal counting mode TCCR3A = 0; // normal counting mode
TCCR3B = _BV(CS31); // set prescaler of 8 TCCR3B = _BV(CS31); // set prescaler of 8
...@@ -170,7 +170,7 @@ static void initISR(timer16_Sequence_t timer) { ...@@ -170,7 +170,7 @@ static void initISR(timer16_Sequence_t timer) {
} }
#endif #endif
#ifdef _useTimer4 #if ENABLED(_useTimer4)
if (timer == _timer4) { if (timer == _timer4) {
TCCR4A = 0; // normal counting mode TCCR4A = 0; // normal counting mode
TCCR4B = _BV(CS41); // set prescaler of 8 TCCR4B = _BV(CS41); // set prescaler of 8
...@@ -180,7 +180,7 @@ static void initISR(timer16_Sequence_t timer) { ...@@ -180,7 +180,7 @@ static void initISR(timer16_Sequence_t timer) {
} }
#endif #endif
#ifdef _useTimer5 #if ENABLED(_useTimer5)
if (timer == _timer5) { if (timer == _timer5) {
TCCR5A = 0; // normal counting mode TCCR5A = 0; // normal counting mode
TCCR5B = _BV(CS51); // set prescaler of 8 TCCR5B = _BV(CS51); // set prescaler of 8
...@@ -230,9 +230,9 @@ static boolean isTimerActive(timer16_Sequence_t timer) { ...@@ -230,9 +230,9 @@ static boolean isTimerActive(timer16_Sequence_t timer) {
/****************** end of static functions ******************************/ /****************** end of static functions ******************************/
Servo::Servo() { Servo::Servo() {
if (ServoCount < MAX_SERVOS) { if ( ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance this->servoIndex = ServoCount++; // assign a servo index to this instance
servo_info[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values servo_info[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
} }
else else
this->servoIndex = INVALID_SERVO; // too many servos this->servoIndex = INVALID_SERVO; // too many servos
......
This diff is collapsed.
...@@ -53,7 +53,7 @@ ...@@ -53,7 +53,7 @@
#define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR) #define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR)
#endif //DRIVER_EXTRUDERS #endif //DRIVER_EXTRUDERS
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
extern bool abort_on_endstop_hit; extern bool abort_on_endstop_hit;
#endif #endif
...@@ -98,17 +98,17 @@ void digipot_current(uint8_t driver, int current); ...@@ -98,17 +98,17 @@ void digipot_current(uint8_t driver, int current);
void microstep_init(); void microstep_init();
void microstep_readings(); void microstep_readings();
#ifdef Z_DUAL_ENDSTOPS #if ENABLED(Z_DUAL_ENDSTOPS)
void In_Homing_Process(bool state); void In_Homing_Process(bool state);
void Lock_z_motor(bool state); void Lock_z_motor(bool state);
void Lock_z2_motor(bool state); void Lock_z2_motor(bool state);
#endif #endif
#ifdef BABYSTEPPING #if ENABLED(BABYSTEPPING)
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif #endif
#ifdef NPR2 // Multiextruder #if ENABLED(NPR2) // Multiextruder
void colorstep(long csteps,const bool direction); void colorstep(long csteps,const bool direction);
#endif #endif
......
...@@ -22,203 +22,203 @@ ...@@ -22,203 +22,203 @@
#include "stepper_indirection.h" #include "stepper_indirection.h"
#include "Configuration.h" #include "Configuration.h"
#ifdef HAVE_TMCDRIVER #if ENABLED(HAVE_TMCDRIVER)
#include <SPI.h> #include <SPI.h>
#include <TMC26XStepper.h> #include <TMC26XStepper.h>
#endif #endif
// Stepper objects of TMC steppers used // Stepper objects of TMC steppers used
#ifdef X_IS_TMC #if ENABLED(X_IS_TMC)
TMC26XStepper stepperX(200,X_ENABLE_PIN,X_STEP_PIN,X_DIR_PIN,X_MAX_CURRENT,X_SENSE_RESISTOR); TMC26XStepper stepperX(200,X_ENABLE_PIN,X_STEP_PIN,X_DIR_PIN,X_MAX_CURRENT,X_SENSE_RESISTOR);
#endif #endif
#ifdef X2_IS_TMC #if ENABLED(X2_IS_TMC)
TMC26XStepper stepperX2(200,X2_ENABLE_PIN,X2_STEP_PIN,X2_DIR_PIN,X2_MAX_CURRENT,X2_SENSE_RESISTOR); TMC26XStepper stepperX2(200,X2_ENABLE_PIN,X2_STEP_PIN,X2_DIR_PIN,X2_MAX_CURRENT,X2_SENSE_RESISTOR);
#endif #endif
#ifdef Y_IS_TMC #if ENABLED(Y_IS_TMC)
TMC26XStepper stepperY(200,Y_ENABLE_PIN,Y_STEP_PIN,Y_DIR_PIN,Y_MAX_CURRENT,Y_SENSE_RESISTOR); TMC26XStepper stepperY(200,Y_ENABLE_PIN,Y_STEP_PIN,Y_DIR_PIN,Y_MAX_CURRENT,Y_SENSE_RESISTOR);
#endif #endif
#ifdef Y2_IS_TMC #if ENABLED(Y2_IS_TMC)
TMC26XStepper stepperY2(200,Y2_ENABLE_PIN,Y2_STEP_PIN,Y2_DIR_PIN,Y2_MAX_CURRENT,Y2_SENSE_RESISTOR); TMC26XStepper stepperY2(200,Y2_ENABLE_PIN,Y2_STEP_PIN,Y2_DIR_PIN,Y2_MAX_CURRENT,Y2_SENSE_RESISTOR);
#endif #endif
#ifdef Z_IS_TMC #if ENABLED(Z_IS_TMC)
TMC26XStepper stepperZ(200,Z_ENABLE_PIN,Z_STEP_PIN,Z_DIR_PIN,Z_MAX_CURRENT,Z_SENSE_RESISTOR); TMC26XStepper stepperZ(200,Z_ENABLE_PIN,Z_STEP_PIN,Z_DIR_PIN,Z_MAX_CURRENT,Z_SENSE_RESISTOR);
#endif #endif
#ifdef Z2_IS_TMC #if ENABLED(Z2_IS_TMC)
TMC26XStepper stepperZ2(200,Z2_ENABLE_PIN,Z2_STEP_PIN,Z2_DIR_PIN,Z2_MAX_CURRENT,Z2_SENSE_RESISTOR); TMC26XStepper stepperZ2(200,Z2_ENABLE_PIN,Z2_STEP_PIN,Z2_DIR_PIN,Z2_MAX_CURRENT,Z2_SENSE_RESISTOR);
#endif #endif
#ifdef E0_IS_TMC #if ENABLED(E0_IS_TMC)
TMC26XStepper stepperE0(200,E0_ENABLE_PIN,E0_STEP_PIN,E0_DIR_PIN,E0_MAX_CURRENT,E0_SENSE_RESISTOR); TMC26XStepper stepperE0(200,E0_ENABLE_PIN,E0_STEP_PIN,E0_DIR_PIN,E0_MAX_CURRENT,E0_SENSE_RESISTOR);
#endif #endif
#ifdef E1_IS_TMC #if ENABLED(E1_IS_TMC)
TMC26XStepper stepperE1(200,E1_ENABLE_PIN,E1_STEP_PIN,E1_DIR_PIN,E1_MAX_CURRENT,E1_SENSE_RESISTOR); TMC26XStepper stepperE1(200,E1_ENABLE_PIN,E1_STEP_PIN,E1_DIR_PIN,E1_MAX_CURRENT,E1_SENSE_RESISTOR);
#endif #endif
#ifdef E2_IS_TMC #if ENABLED(E2_IS_TMC)
TMC26XStepper stepperE2(200,E2_ENABLE_PIN,E2_STEP_PIN,E2_DIR_PIN,E2_MAX_CURRENT,E2_SENSE_RESISTOR); TMC26XStepper stepperE2(200,E2_ENABLE_PIN,E2_STEP_PIN,E2_DIR_PIN,E2_MAX_CURRENT,E2_SENSE_RESISTOR);
#endif #endif
#ifdef E3_IS_TMC #if ENABLED(E3_IS_TMC)
TMC26XStepper stepperE3(200,E3_ENABLE_PIN,E3_STEP_PIN,E3_DIR_PIN,E3_MAX_CURRENT,E3_SENSE_RESISTOR); TMC26XStepper stepperE3(200,E3_ENABLE_PIN,E3_STEP_PIN,E3_DIR_PIN,E3_MAX_CURRENT,E3_SENSE_RESISTOR);
#endif #endif
#ifdef HAVE_TMCDRIVER #if ENABLED(HAVE_TMCDRIVER)
void tmc_init() void tmc_init()
{ {
#ifdef X_IS_TMC #if ENABLED(X_IS_TMC)
stepperX.setMicrosteps(X_MICROSTEPS); stepperX.setMicrosteps(X_MICROSTEPS);
stepperX.start(); stepperX.start();
#endif #endif
#ifdef X2_IS_TMC #if ENABLED(X2_IS_TMC)
stepperX2.setMicrosteps(X2_MICROSTEPS); stepperX2.setMicrosteps(X2_MICROSTEPS);
stepperX2.start(); stepperX2.start();
#endif #endif
#ifdef Y_IS_TMC #if ENABLED(Y_IS_TMC)
stepperY.setMicrosteps(Y_MICROSTEPS); stepperY.setMicrosteps(Y_MICROSTEPS);
stepperY.start(); stepperY.start();
#endif #endif
#ifdef Y2_IS_TMC #if ENABLED(Y2_IS_TMC)
stepperY2.setMicrosteps(Y2_MICROSTEPS); stepperY2.setMicrosteps(Y2_MICROSTEPS);
stepperY2.start(); stepperY2.start();
#endif #endif
#ifdef Z_IS_TMC #if ENABLED(Z_IS_TMC)
stepperZ.setMicrosteps(Z_MICROSTEPS); stepperZ.setMicrosteps(Z_MICROSTEPS);
stepperZ.start(); stepperZ.start();
#endif #endif
#ifdef Z2_IS_TMC #if ENABLED(Z2_IS_TMC)
stepperZ2.setMicrosteps(Z2_MICROSTEPS); stepperZ2.setMicrosteps(Z2_MICROSTEPS);
stepperZ2.start(); stepperZ2.start();
#endif #endif
#ifdef E0_IS_TMC #if ENABLED(E0_IS_TMC)
stepperE0.setMicrosteps(E0_MICROSTEPS); stepperE0.setMicrosteps(E0_MICROSTEPS);
stepperE0.start(); stepperE0.start();
#endif #endif
#ifdef E1_IS_TMC #if ENABLED(E1_IS_TMC)
stepperE1.setMicrosteps(E1_MICROSTEPS); stepperE1.setMicrosteps(E1_MICROSTEPS);
stepperE1.start(); stepperE1.start();
#endif #endif
#ifdef E2_IS_TMC #if ENABLED(E2_IS_TMC)
stepperE2.setMicrosteps(E2_MICROSTEPS); stepperE2.setMicrosteps(E2_MICROSTEPS);
stepperE2.start(); stepperE2.start();
#endif #endif
#ifdef E3_IS_TMC #if ENABLED(E3_IS_TMC)
stepperE3.setMicrosteps(E3_MICROSTEPS); stepperE3.setMicrosteps(E3_MICROSTEPS);
stepperE3.start(); stepperE3.start();
#endif #endif
} }
#endif #endif
// L6470 Driver objects and inits // L6470 Driver objects and inits
#ifdef HAVE_L6470DRIVER #if ENABLED(HAVE_L6470DRIVER)
#include <SPI.h> #include <SPI.h>
#include <L6470.h> #include <L6470.h>
#endif #endif
// L6470 Stepper objects // L6470 Stepper objects
#ifdef X_IS_L6470 #if ENABLED(X_IS_L6470)
L6470 stepperX(X_ENABLE_PIN); L6470 stepperX(X_ENABLE_PIN);
#endif #endif
#ifdef X2_IS_L6470 #if ENABLED(X2_IS_L6470)
L6470 stepperX2(X2_ENABLE_PIN); L6470 stepperX2(X2_ENABLE_PIN);
#endif #endif
#ifdef Y_IS_L6470 #if ENABLED(Y_IS_L6470)
L6470 stepperY(Y_ENABLE_PIN); L6470 stepperY(Y_ENABLE_PIN);
#endif #endif
#ifdef Y2_IS_L6470 #if ENABLED(Y2_IS_L6470)
L6470 stepperY2(Y2_ENABLE_PIN); L6470 stepperY2(Y2_ENABLE_PIN);
#endif #endif
#ifdef Z_IS_L6470 #if ENABLED(Z_IS_L6470)
L6470 stepperZ(Z_ENABLE_PIN); L6470 stepperZ(Z_ENABLE_PIN);
#endif #endif
#ifdef Z2_IS_L6470 #if ENABLED(Z2_IS_L6470)
L6470 stepperZ2(Z2_ENABLE_PIN); L6470 stepperZ2(Z2_ENABLE_PIN);
#endif #endif
#ifdef E0_IS_L6470 #if ENABLED(E0_IS_L6470)
L6470 stepperE0(E0_ENABLE_PIN); L6470 stepperE0(E0_ENABLE_PIN);
#endif #endif
#ifdef E1_IS_L6470 #if ENABLED(E1_IS_L6470)
L6470 stepperE1(E1_ENABLE_PIN); L6470 stepperE1(E1_ENABLE_PIN);
#endif #endif
#ifdef E2_IS_L6470 #if ENABLED(E2_IS_L6470)
L6470 stepperE2(E2_ENABLE_PIN); L6470 stepperE2(E2_ENABLE_PIN);
#endif #endif
#ifdef E3_IS_L6470 #if ENABLED(E3_IS_L6470)
L6470 stepperE3(E3_ENABLE_PIN); L6470 stepperE3(E3_ENABLE_PIN);
#endif #endif
// init routine // init routine
#ifdef HAVE_L6470DRIVER #if ENABLED(HAVE_L6470DRIVER)
void L6470_init() void L6470_init()
{ {
#ifdef X_IS_L6470 #if ENABLED(X_IS_L6470)
stepperX.init(X_K_VAL); stepperX.init(X_K_VAL);
stepperX.softFree(); stepperX.softFree();
stepperX.setMicroSteps(X_MICROSTEPS); stepperX.setMicroSteps(X_MICROSTEPS);
stepperX.setOverCurrent(X_OVERCURRENT); //set overcurrent protection stepperX.setOverCurrent(X_OVERCURRENT); //set overcurrent protection
stepperX.setStallCurrent(X_STALLCURRENT); stepperX.setStallCurrent(X_STALLCURRENT);
#endif #endif
#ifdef X2_IS_L6470 #if ENABLED(X2_IS_L6470)
stepperX2.init(X2_K_VAL); stepperX2.init(X2_K_VAL);
stepperX2.softFree(); stepperX2.softFree();
stepperX2.setMicroSteps(X2_MICROSTEPS); stepperX2.setMicroSteps(X2_MICROSTEPS);
stepperX2.setOverCurrent(X2_OVERCURRENT); //set overcurrent protection stepperX2.setOverCurrent(X2_OVERCURRENT); //set overcurrent protection
stepperX2.setStallCurrent(X2_STALLCURRENT); stepperX2.setStallCurrent(X2_STALLCURRENT);
#endif #endif
#ifdef Y_IS_L6470 #if ENABLED(Y_IS_L6470)
stepperY.init(Y_K_VAL); stepperY.init(Y_K_VAL);
stepperY.softFree(); stepperY.softFree();
stepperY.setMicroSteps(Y_MICROSTEPS); stepperY.setMicroSteps(Y_MICROSTEPS);
stepperY.setOverCurrent(Y_OVERCURRENT); //set overcurrent protection stepperY.setOverCurrent(Y_OVERCURRENT); //set overcurrent protection
stepperY.setStallCurrent(Y_STALLCURRENT); stepperY.setStallCurrent(Y_STALLCURRENT);
#endif #endif
#ifdef Y2_IS_L6470 #if ENABLED(Y2_IS_L6470)
stepperY2.init(Y2_K_VAL); stepperY2.init(Y2_K_VAL);
stepperY2.softFree(); stepperY2.softFree();
stepperY2.setMicroSteps(Y2_MICROSTEPS); stepperY2.setMicroSteps(Y2_MICROSTEPS);
stepperY2.setOverCurrent(Y2_OVERCURRENT); //set overcurrent protection stepperY2.setOverCurrent(Y2_OVERCURRENT); //set overcurrent protection
stepperY2.setStallCurrent(Y2_STALLCURRENT); stepperY2.setStallCurrent(Y2_STALLCURRENT);
#endif #endif
#ifdef Z_IS_L6470 #if ENABLED(Z_IS_L6470)
stepperZ.init(Z_K_VAL); stepperZ.init(Z_K_VAL);
stepperZ.softFree(); stepperZ.softFree();
stepperZ.setMicroSteps(Z_MICROSTEPS); stepperZ.setMicroSteps(Z_MICROSTEPS);
stepperZ.setOverCurrent(Z_OVERCURRENT); //set overcurrent protection stepperZ.setOverCurrent(Z_OVERCURRENT); //set overcurrent protection
stepperZ.setStallCurrent(Z_STALLCURRENT); stepperZ.setStallCurrent(Z_STALLCURRENT);
#endif #endif
#ifdef Z2_IS_L6470 #if ENABLED(Z2_IS_L6470)
stepperZ2.init(Z2_K_VAL); stepperZ2.init(Z2_K_VAL);
stepperZ2.softFree(); stepperZ2.softFree();
stepperZ2.setMicroSteps(Z2_MICROSTEPS); stepperZ2.setMicroSteps(Z2_MICROSTEPS);
stepperZ2.setOverCurrent(Z2_OVERCURRENT); //set overcurrent protection stepperZ2.setOverCurrent(Z2_OVERCURRENT); //set overcurrent protection
stepperZ2.setStallCurrent(Z2_STALLCURRENT); stepperZ2.setStallCurrent(Z2_STALLCURRENT);
#endif #endif
#ifdef E0_IS_L6470 #if ENABLED(E0_IS_L6470)
stepperE0.init(E0_K_VAL); stepperE0.init(E0_K_VAL);
stepperE0.softFree(); stepperE0.softFree();
stepperE0.setMicroSteps(E0_MICROSTEPS); stepperE0.setMicroSteps(E0_MICROSTEPS);
stepperE0.setOverCurrent(E0_OVERCURRENT); //set overcurrent protection stepperE0.setOverCurrent(E0_OVERCURRENT); //set overcurrent protection
stepperE0.setStallCurrent(E0_STALLCURRENT); stepperE0.setStallCurrent(E0_STALLCURRENT);
#endif #endif
#ifdef E1_IS_L6470 #if ENABLED(E1_IS_L6470)
stepperE1.init(E1_K_VAL); stepperE1.init(E1_K_VAL);
stepperE1.softFree(); stepperE1.softFree();
stepperE1.setMicroSteps(E1_MICROSTEPS); stepperE1.setMicroSteps(E1_MICROSTEPS);
stepperE1.setOverCurrent(E1_OVERCURRENT); //set overcurrent protection stepperE1.setOverCurrent(E1_OVERCURRENT); //set overcurrent protection
stepperE1.setStallCurrent(E1_STALLCURRENT); stepperE1.setStallCurrent(E1_STALLCURRENT);
#endif #endif
#ifdef E2_IS_L6470 #if ENABLED(E2_IS_L6470)
stepperE2.init(E2_K_VAL); stepperE2.init(E2_K_VAL);
stepperE2.softFree(); stepperE2.softFree();
stepperE2.setMicroSteps(E2_MICROSTEPS); stepperE2.setMicroSteps(E2_MICROSTEPS);
stepperE2.setOverCurrent(E2_OVERCURRENT); //set overcurrent protection stepperE2.setOverCurrent(E2_OVERCURRENT); //set overcurrent protection
stepperE2.setStallCurrent(E2_STALLCURRENT); stepperE2.setStallCurrent(E2_STALLCURRENT);
#endif #endif
#ifdef E3_IS_L6470 #if ENABLED(E3_IS_L6470)
stepperE3.init(E3_K_VAL); stepperE3.init(E3_K_VAL);
stepperE3.softFree(); stepperE3.softFree();
stepperE3.setMicroSteps(E3_MICROSTEPS); stepperE3.setMicroSteps(E3_MICROSTEPS);
stepperE3.setOverCurrent(E3_OVERCURRENT); //set overcurrent protection stepperE3.setOverCurrent(E3_OVERCURRENT); //set overcurrent protection
stepperE3.setStallCurrent(E3_STALLCURRENT); stepperE3.setStallCurrent(E3_STALLCURRENT);
#endif #endif
} }
#endif #endif
...@@ -22,6 +22,8 @@ ...@@ -22,6 +22,8 @@
#ifndef STEPPER_INDIRECTION_H #ifndef STEPPER_INDIRECTION_H
#define STEPPER_INDIRECTION_H #define STEPPER_INDIRECTION_H
#include "macros.h"
// X motor // X motor
#define X_STEP_INIT SET_OUTPUT(X_STEP_PIN) #define X_STEP_INIT SET_OUTPUT(X_STEP_PIN)
#define X_STEP_WRITE(STATE) WRITE(X_STEP_PIN,STATE) #define X_STEP_WRITE(STATE) WRITE(X_STEP_PIN,STATE)
...@@ -156,12 +158,12 @@ ...@@ -156,12 +158,12 @@
// Pin redefines for TMC drivers. // Pin redefines for TMC drivers.
// TMC26X drivers have step and dir on normal pins, but everything else via SPI // TMC26X drivers have step and dir on normal pins, but everything else via SPI
////////////////////////////////// //////////////////////////////////
#ifdef HAVE_TMCDRIVER #if ENABLED(HAVE_TMCDRIVER)
#include <SPI.h> #include <SPI.h>
#include <TMC26XStepper.h> #include <TMC26XStepper.h>
void tmc_init(); void tmc_init();
#ifdef X_IS_TMC #if ENABLED(X_IS_TMC)
extern TMC26XStepper stepperX; extern TMC26XStepper stepperX;
#undef X_ENABLE_INIT #undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0) #define X_ENABLE_INIT ((void)0)
...@@ -173,7 +175,7 @@ ...@@ -173,7 +175,7 @@
#define X_ENABLE_READ stepperX.isEnabled() #define X_ENABLE_READ stepperX.isEnabled()
#endif #endif
#ifdef X2_IS_TMC #if ENABLED(X2_IS_TMC)
extern TMC26XStepper stepperX2; extern TMC26XStepper stepperX2;
#undef X2_ENABLE_INIT #undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0) #define X2_ENABLE_INIT ((void)0)
...@@ -184,7 +186,7 @@ ...@@ -184,7 +186,7 @@
#undef X2_ENABLE_READ #undef X2_ENABLE_READ
#define X2_ENABLE_READ stepperX2.isEnabled() #define X2_ENABLE_READ stepperX2.isEnabled()
#endif #endif
#ifdef Y_IS_TMC #if ENABLED(Y_IS_TMC)
extern TMC26XStepper stepperY; extern TMC26XStepper stepperY;
#undef Y_ENABLE_INIT #undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0) #define Y_ENABLE_INIT ((void)0)
...@@ -195,7 +197,7 @@ ...@@ -195,7 +197,7 @@
#undef Y_ENABLE_READ #undef Y_ENABLE_READ
#define Y_ENABLE_READ stepperY.isEnabled() #define Y_ENABLE_READ stepperY.isEnabled()
#endif #endif
#ifdef Y2_IS_TMC #if ENABLED(Y2_IS_TMC)
extern TMC26XStepper stepperY2; extern TMC26XStepper stepperY2;
#undef Y2_ENABLE_INIT #undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0) #define Y2_ENABLE_INIT ((void)0)
...@@ -206,7 +208,7 @@ ...@@ -206,7 +208,7 @@
#undef Y2_ENABLE_READ #undef Y2_ENABLE_READ
#define Y2_ENABLE_READ stepperY2.isEnabled() #define Y2_ENABLE_READ stepperY2.isEnabled()
#endif #endif
#ifdef Z_IS_TMC #if ENABLED(Z_IS_TMC)
extern TMC26XStepper stepperZ; extern TMC26XStepper stepperZ;
#undef Z_ENABLE_INIT #undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0) #define Z_ENABLE_INIT ((void)0)
...@@ -217,7 +219,7 @@ ...@@ -217,7 +219,7 @@
#undef Z_ENABLE_READ #undef Z_ENABLE_READ
#define Z_ENABLE_READ stepperZ.isEnabled() #define Z_ENABLE_READ stepperZ.isEnabled()
#endif #endif
#ifdef Z2_IS_TMC #if ENABLED(Z2_IS_TMC)
extern TMC26XStepper stepperZ2; extern TMC26XStepper stepperZ2;
#undef Z2_ENABLE_INIT #undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0) #define Z2_ENABLE_INIT ((void)0)
...@@ -228,7 +230,7 @@ ...@@ -228,7 +230,7 @@
#undef Z2_ENABLE_READ #undef Z2_ENABLE_READ
#define Z2_ENABLE_READ stepperZ2.isEnabled() #define Z2_ENABLE_READ stepperZ2.isEnabled()
#endif #endif
#ifdef E0_IS_TMC #if ENABLED(E0_IS_TMC)
extern TMC26XStepper stepperE0; extern TMC26XStepper stepperE0;
#undef E0_ENABLE_INIT #undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0) #define E0_ENABLE_INIT ((void)0)
...@@ -239,7 +241,7 @@ ...@@ -239,7 +241,7 @@
#undef E0_ENABLE_READ #undef E0_ENABLE_READ
#define E0_ENABLE_READ stepperE0.isEnabled() #define E0_ENABLE_READ stepperE0.isEnabled()
#endif #endif
#ifdef E1_IS_TMC #if ENABLED(E1_IS_TMC)
extern TMC26XStepper stepperE1; extern TMC26XStepper stepperE1;
#undef E1_ENABLE_INIT #undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0) #define E1_ENABLE_INIT ((void)0)
...@@ -250,7 +252,7 @@ ...@@ -250,7 +252,7 @@
#undef E1_ENABLE_READ #undef E1_ENABLE_READ
#define E1_ENABLE_READ stepperE1.isEnabled() #define E1_ENABLE_READ stepperE1.isEnabled()
#endif #endif
#ifdef E2_IS_TMC #if ENABLED(E2_IS_TMC)
extern TMC26XStepper stepperE2; extern TMC26XStepper stepperE2;
#undef E2_ENABLE_INIT #undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0) #define E2_ENABLE_INIT ((void)0)
...@@ -261,7 +263,7 @@ ...@@ -261,7 +263,7 @@
#undef E2_ENABLE_READ #undef E2_ENABLE_READ
#define E2_ENABLE_READ stepperE2.isEnabled() #define E2_ENABLE_READ stepperE2.isEnabled()
#endif #endif
#ifdef E3_IS_TMC #if ENABLED(E3_IS_TMC)
extern TMC26XStepper stepperE3; extern TMC26XStepper stepperE3;
#undef E3_ENABLE_INIT #undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0) #define E3_ENABLE_INIT ((void)0)
...@@ -279,13 +281,13 @@ ...@@ -279,13 +281,13 @@
// Pin redefines for L6470 drivers. // Pin redefines for L6470 drivers.
// L640 drivers have step on normal pins, but dir and everything else via SPI // L640 drivers have step on normal pins, but dir and everything else via SPI
////////////////////////////////// //////////////////////////////////
#ifdef HAVE_L6470DRIVER #if ENABLED(HAVE_L6470DRIVER)
#include <SPI.h> #include <SPI.h>
#include <L6470.h> #include <L6470.h>
void L6470_init(); void L6470_init();
#ifdef X_IS_L6470 #if ENABLED(X_IS_L6470)
extern L6470 stepperX; extern L6470 stepperX;
#undef X_ENABLE_INIT #undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0) #define X_ENABLE_INIT ((void)0)
...@@ -306,7 +308,7 @@ ...@@ -306,7 +308,7 @@
#define X_DIR_READ (stepperX.getStatus() & STATUS_DIR) #define X_DIR_READ (stepperX.getStatus() & STATUS_DIR)
#endif #endif
#ifdef X2_IS_L6470 #if ENABLED(X2_IS_L6470)
extern L6470 stepperX2; extern L6470 stepperX2;
#undef X2_ENABLE_INIT #undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0) #define X2_ENABLE_INIT ((void)0)
...@@ -326,7 +328,7 @@ ...@@ -326,7 +328,7 @@
#undef X2_DIR_READ #undef X2_DIR_READ
#define X2_DIR_READ (stepperX2.getStatus() & STATUS_DIR) #define X2_DIR_READ (stepperX2.getStatus() & STATUS_DIR)
#endif #endif
#ifdef Y_IS_L6470 #if ENABLED(Y_IS_L6470)
extern L6470 stepperY; extern L6470 stepperY;
#undef Y_ENABLE_INIT #undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0) #define Y_ENABLE_INIT ((void)0)
...@@ -346,7 +348,7 @@ ...@@ -346,7 +348,7 @@
#undef Y_DIR_READ #undef Y_DIR_READ
#define Y_DIR_READ (stepperY.getStatus() & STATUS_DIR) #define Y_DIR_READ (stepperY.getStatus() & STATUS_DIR)
#endif #endif
#ifdef Y2_IS_L6470 #if ENABLED(Y2_IS_L6470)
extern L6470 stepperY2; extern L6470 stepperY2;
#undef Y2_ENABLE_INIT #undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0) #define Y2_ENABLE_INIT ((void)0)
...@@ -366,7 +368,7 @@ ...@@ -366,7 +368,7 @@
#undef Y2_DIR_READ #undef Y2_DIR_READ
#define Y2_DIR_READ (stepperY2.getStatus() & STATUS_DIR) #define Y2_DIR_READ (stepperY2.getStatus() & STATUS_DIR)
#endif #endif
#ifdef Z_IS_L6470 #if ENABLED(Z_IS_L6470)
extern L6470 stepperZ; extern L6470 stepperZ;
#undef Z_ENABLE_INIT #undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0) #define Z_ENABLE_INIT ((void)0)
...@@ -386,7 +388,7 @@ ...@@ -386,7 +388,7 @@
#undef Y_DIR_READ #undef Y_DIR_READ
#define Y_DIR_READ (stepperZ.getStatus() & STATUS_DIR) #define Y_DIR_READ (stepperZ.getStatus() & STATUS_DIR)
#endif #endif
#ifdef Z2_IS_L6470 #if ENABLED(Z2_IS_L6470)
extern L6470 stepperZ2; extern L6470 stepperZ2;
#undef Z2_ENABLE_INIT #undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0) #define Z2_ENABLE_INIT ((void)0)
...@@ -406,7 +408,7 @@ ...@@ -406,7 +408,7 @@
#undef Y2_DIR_READ #undef Y2_DIR_READ
#define Y2_DIR_READ (stepperZ2.getStatus() & STATUS_DIR) #define Y2_DIR_READ (stepperZ2.getStatus() & STATUS_DIR)
#endif #endif
#ifdef E0_IS_L6470 #if ENABLED(E0_IS_L6470)
extern L6470 stepperE0; extern L6470 stepperE0;
#undef E0_ENABLE_INIT #undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0) #define E0_ENABLE_INIT ((void)0)
...@@ -426,7 +428,7 @@ ...@@ -426,7 +428,7 @@
#undef E0_DIR_READ #undef E0_DIR_READ
#define E0_DIR_READ (stepperE0.getStatus() & STATUS_DIR) #define E0_DIR_READ (stepperE0.getStatus() & STATUS_DIR)
#endif #endif
#ifdef E1_IS_L6470 #if ENABLED(E1_IS_L6470)
extern L6470 stepperE1; extern L6470 stepperE1;
#undef E1_ENABLE_INIT #undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0) #define E1_ENABLE_INIT ((void)0)
...@@ -446,7 +448,7 @@ ...@@ -446,7 +448,7 @@
#undef E1_DIR_READ #undef E1_DIR_READ
#define E1_DIR_READ (stepperE1.getStatus() & STATUS_DIR) #define E1_DIR_READ (stepperE1.getStatus() & STATUS_DIR)
#endif #endif
#ifdef E2_IS_L6470 #if ENABLED(E2_IS_L6470)
extern L6470 stepperE2; extern L6470 stepperE2;
#undef E2_ENABLE_INIT #undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0) #define E2_ENABLE_INIT ((void)0)
...@@ -466,7 +468,7 @@ ...@@ -466,7 +468,7 @@
#undef E2_DIR_READ #undef E2_DIR_READ
#define E2_DIR_READ (stepperE2.getStatus() & STATUS_DIR) #define E2_DIR_READ (stepperE2.getStatus() & STATUS_DIR)
#endif #endif
#ifdef E3_IS_L6470 #if ENABLED(E3_IS_L6470)
extern L6470 stepperE3; extern L6470 stepperE3;
#undef E3_ENABLE_INIT #undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0) #define E3_ENABLE_INIT ((void)0)
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
#include "Marlin.h" #include "Marlin.h"
#ifdef U8GLIB_ST7920 #if ENABLED(U8GLIB_ST7920)
//set optimization so ARDUINO optimizes this file //set optimization so ARDUINO optimizes this file
#pragma GCC optimize (3) #pragma GCC optimize (3)
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment