Merge branch 'Marlin_v1' of https://github.com/ErikZalm/Marlin into Marlin_v1
This should fix issues with pull request 467, I hope. Conflicts: Marlin/Configuration.h Marlin/Marlin.pde Marlin/ultralcd_implementation_hitachi_HD44780.h
This commit is contained in:
commit
6a81291c57
|
@ -2,7 +2,7 @@
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
// This configurtion file contains the basic settings.
|
// This configurtion file contains the basic settings.
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
// Advanced settings can be found in Configuration_adv.h
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
||||||
|
|
||||||
//User specified version info of this build to display in [Pronterface, etc] terminal window during startup.
|
//User specified version info of this build to display in [Pronterface, etc] terminal window during startup.
|
||||||
|
@ -43,6 +43,8 @@
|
||||||
// 82 = Brainwave (AT90USB646)
|
// 82 = Brainwave (AT90USB646)
|
||||||
// 9 = Gen3+
|
// 9 = Gen3+
|
||||||
// 70 = Megatronics
|
// 70 = Megatronics
|
||||||
|
// 701= Megatronics v2.0
|
||||||
|
// 702= Minitronics v1.0
|
||||||
// 90 = Alpha OMCA board
|
// 90 = Alpha OMCA board
|
||||||
// 91 = Final OMCA board
|
// 91 = Final OMCA board
|
||||||
// 301 = Rambo
|
// 301 = Rambo
|
||||||
|
@ -52,6 +54,9 @@
|
||||||
#define MOTHERBOARD 7
|
#define MOTHERBOARD 7
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// This defines the number of extruders
|
||||||
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
||||||
// 1 = ATX
|
// 1 = ATX
|
||||||
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||||
|
@ -79,24 +84,28 @@
|
||||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
// 51 is 100k thermistor - EPCOS (1k pullup)
|
||||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
||||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan) (1k pullup)
|
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan) (1k pullup)
|
||||||
|
|
||||||
#define TEMP_SENSOR_0 -1
|
#define TEMP_SENSOR_0 -1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 -1
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
#define TEMP_SENSOR_BED 0
|
#define TEMP_SENSOR_BED 0
|
||||||
|
|
||||||
|
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
|
||||||
|
//#define TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
|
||||||
|
|
||||||
// Actual temperature must be close to target for this long before M109 returns success
|
// Actual temperature must be close to target for this long before M109 returns success
|
||||||
#define TEMP_RESIDENCY_TIME 10 // (seconds)
|
#define TEMP_RESIDENCY_TIME 10 // (seconds)
|
||||||
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
|
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
|
||||||
#define TEMP_WINDOW 1 // (degC) Window around target to start the recidency timer x degC early.
|
#define TEMP_WINDOW 1 // (degC) Window around target to start the recidency timer x degC early.
|
||||||
|
|
||||||
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
|
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
|
||||||
// to check that the wiring to the thermistor is not broken.
|
// to check that the wiring to the thermistor is not broken.
|
||||||
// Otherwise this would lead to the heater being powered on all the time.
|
// Otherwise this would lead to the heater being powered on all the time.
|
||||||
#define HEATER_0_MINTEMP 5
|
#define HEATER_0_MINTEMP 5
|
||||||
#define HEATER_1_MINTEMP 5
|
#define HEATER_1_MINTEMP 5
|
||||||
|
@ -122,7 +131,7 @@
|
||||||
#define BANG_MAX 256 // limits current to nozzle while in bang-bang mode; 256=full current
|
#define BANG_MAX 256 // limits current to nozzle while in bang-bang mode; 256=full current
|
||||||
#define PID_MAX 256 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 256=full current
|
#define PID_MAX 256 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 256=full current
|
||||||
#ifdef PIDTEMP
|
#ifdef 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 PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
|
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
|
@ -133,15 +142,15 @@
|
||||||
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
||||||
// Ultimaker
|
// Ultimaker
|
||||||
#define DEFAULT_Kp 22.2
|
#define DEFAULT_Kp 22.2
|
||||||
#define DEFAULT_Ki 1.08
|
#define DEFAULT_Ki 1.08
|
||||||
#define DEFAULT_Kd 114
|
#define DEFAULT_Kd 114
|
||||||
|
|
||||||
// Makergear
|
// Makergear
|
||||||
// #define DEFAULT_Kp 7.0
|
// #define DEFAULT_Kp 7.0
|
||||||
// #define DEFAULT_Ki 0.1
|
// #define DEFAULT_Ki 0.1
|
||||||
// #define DEFAULT_Kd 12
|
// #define DEFAULT_Kd 12
|
||||||
|
|
||||||
// Mendel Parts V9 on 12V
|
// Mendel Parts V9 on 12V
|
||||||
// #define DEFAULT_Kp 63.0
|
// #define DEFAULT_Kp 63.0
|
||||||
// #define DEFAULT_Ki 2.25
|
// #define DEFAULT_Ki 2.25
|
||||||
// #define DEFAULT_Kd 440
|
// #define DEFAULT_Kd 440
|
||||||
|
@ -150,11 +159,11 @@
|
||||||
// Bed Temperature Control
|
// Bed Temperature Control
|
||||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
||||||
//
|
//
|
||||||
// uncomment this to enable PID on the bed. It uses the same ferquency PWM as the extruder.
|
// uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
||||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
||||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
||||||
// If your configuration is significantly different than this and you don't understand the issues involved, you proabaly
|
// If your configuration is significantly different than this and you don't understand the issues involved, you proabaly
|
||||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||||
// If this is enabled, find your own PID constants below.
|
// If this is enabled, find your own PID constants below.
|
||||||
//#define PIDTEMPBED
|
//#define PIDTEMPBED
|
||||||
|
@ -224,9 +233,9 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
|
||||||
const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
||||||
const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
||||||
const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
//#define DISABLE_MAX_ENDSTOPS
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -281,13 +290,13 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
// default settings
|
// default settings
|
||||||
|
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for ultimaker
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for ultimaker
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
||||||
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
|
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
||||||
|
|
||||||
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
|
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
|
||||||
|
@ -308,7 +317,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
// EEPROM
|
// EEPROM
|
||||||
// the microcontroller can store settings in the EEPROM, e.g. max velocity...
|
// the microcontroller can store settings in the EEPROM, e.g. max velocity...
|
||||||
// M500 - stores paramters in EEPROM
|
// M500 - stores paramters in EEPROM
|
||||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||||
//define this to enable eeprom support
|
//define this to enable eeprom support
|
||||||
//#define EEPROM_SETTINGS
|
//#define EEPROM_SETTINGS
|
||||||
|
@ -316,9 +325,18 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
// please keep turned on if you can.
|
// please keep turned on if you can.
|
||||||
//#define EEPROM_CHITCHAT
|
//#define EEPROM_CHITCHAT
|
||||||
|
|
||||||
|
// Preheat Constants
|
||||||
|
#define PLA_PREHEAT_HOTEND_TEMP 180
|
||||||
|
#define PLA_PREHEAT_HPB_TEMP 70
|
||||||
|
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
||||||
|
|
||||||
|
#define ABS_PREHEAT_HOTEND_TEMP 240
|
||||||
|
#define ABS_PREHEAT_HPB_TEMP 100
|
||||||
|
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
||||||
|
|
||||||
//LCD and SD support
|
//LCD and SD support
|
||||||
//#define ULTRA_LCD //general lcd support, also 16x2
|
//#define ULTRA_LCD //general lcd support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
||||||
|
|
||||||
|
@ -339,6 +357,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
// ==> 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 REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
|
||||||
|
//#define REPRAPWORLD_KEYPAD
|
||||||
|
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
|
||||||
|
|
||||||
// The Elefu RA Board Control Panel
|
// The Elefu RA Board Control Panel
|
||||||
// http://www.elefu.com/index.php?route=product/product&product_id=53
|
// http://www.elefu.com/index.php?route=product/product&product_id=53
|
||||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARUDINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARUDINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||||
|
@ -356,6 +379,10 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
#define NEWPANEL
|
#define NEWPANEL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(REPRAPWORLD_KEYPAD)
|
||||||
|
#define NEWPANEL
|
||||||
|
#define ULTIPANEL
|
||||||
|
#endif
|
||||||
#if defined(RA_CONTROL_PANEL)
|
#if defined(RA_CONTROL_PANEL)
|
||||||
#define ULTIPANEL
|
#define ULTIPANEL
|
||||||
#define NEWPANEL
|
#define NEWPANEL
|
||||||
|
@ -363,36 +390,67 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Preheat Constants
|
//I2C PANELS
|
||||||
#define PLA_PREHEAT_HOTEND_TEMP 180
|
|
||||||
#define PLA_PREHEAT_HPB_TEMP 70
|
|
||||||
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
|
||||||
|
|
||||||
#define ABS_PREHEAT_HOTEND_TEMP 240
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
#define ABS_PREHEAT_HPB_TEMP 100
|
#ifdef LCD_I2C_SAINSMART_YWROBOT
|
||||||
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
// This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home )
|
||||||
|
// Make sure it is placed in the Arduino libraries directory.
|
||||||
|
#define LCD_I2C_TYPE_PCF8575
|
||||||
|
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||||
|
#define NEWPANEL
|
||||||
|
#define ULTIPANEL
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
|
//#define LCD_I2C_PANELOLU2
|
||||||
|
#ifdef LCD_I2C_PANELOLU2
|
||||||
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||||
|
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
|
||||||
|
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
|
||||||
|
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
|
||||||
|
#define LCD_I2C_TYPE_MCP23017
|
||||||
|
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||||
|
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
|
||||||
|
#define NEWPANEL
|
||||||
|
#define ULTIPANEL
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
|
||||||
|
//#define LCD_I2C_VIKI
|
||||||
|
#ifdef LCD_I2C_VIKI
|
||||||
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
|
||||||
|
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
|
||||||
|
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
|
||||||
|
#define LCD_I2C_TYPE_MCP23017
|
||||||
|
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
|
||||||
|
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
|
||||||
|
#define NEWPANEL
|
||||||
|
#define ULTIPANEL
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
// #define NEWPANEL //enable this if you have a click-encoder panel
|
// #define NEWPANEL //enable this if you have a click-encoder panel
|
||||||
#define SDSUPPORT
|
#define SDSUPPORT
|
||||||
#define ULTRA_LCD
|
#define ULTRA_LCD
|
||||||
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
|
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
|
||||||
#define LCD_WIDTH 20
|
#define LCD_WIDTH 20
|
||||||
#define LCD_HEIGHT 5
|
#define LCD_HEIGHT 5
|
||||||
#else
|
#else
|
||||||
#define LCD_WIDTH 20
|
#define LCD_WIDTH 20
|
||||||
#define LCD_HEIGHT 4
|
#define LCD_HEIGHT 4
|
||||||
#endif
|
#endif
|
||||||
#else //no panel but just lcd
|
#else //no panel but just lcd
|
||||||
#ifdef ULTRA_LCD
|
#ifdef ULTRA_LCD
|
||||||
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
|
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
|
||||||
#define LCD_WIDTH 20
|
#define LCD_WIDTH 20
|
||||||
#define LCD_HEIGHT 5
|
#define LCD_HEIGHT 5
|
||||||
#else
|
#else
|
||||||
#define LCD_WIDTH 16
|
#define LCD_WIDTH 16
|
||||||
#define LCD_HEIGHT 2
|
#define LCD_HEIGHT 2
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -406,6 +464,34 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
// SF send wrong arc g-codes when using Arc Point as fillet procedure
|
// SF send wrong arc g-codes when using Arc Point as fillet procedure
|
||||||
//#define SF_ARC_FIX
|
//#define SF_ARC_FIX
|
||||||
|
|
||||||
|
// Support for the BariCUDA Paste Extruder.
|
||||||
|
//#define BARICUDA
|
||||||
|
|
||||||
|
/*********************************************************************\
|
||||||
|
*
|
||||||
|
* R/C SERVO support
|
||||||
|
*
|
||||||
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
|
*
|
||||||
|
**********************************************************************/
|
||||||
|
|
||||||
|
// Number of servos
|
||||||
|
//
|
||||||
|
// 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
|
||||||
|
// leaving it undefined or defining as 0 will disable the servo subsystem
|
||||||
|
// If unsure, leave commented / disabled
|
||||||
|
//
|
||||||
|
//#define NUM_SERVOS 3 // Servo index starts with 0
|
||||||
|
|
||||||
|
// Servo Endstops
|
||||||
|
//
|
||||||
|
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
|
||||||
|
// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
|
||||||
|
//
|
||||||
|
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
|
||||||
|
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
||||||
|
|
|
@ -63,21 +63,31 @@
|
||||||
//This is for controlling a fan to cool down the stepper drivers
|
//This is for controlling a fan to cool down the stepper drivers
|
||||||
//it will turn on when any driver is enabled
|
//it will turn on when any driver is enabled
|
||||||
//and turn off after the set amount of seconds from last driver being disabled again
|
//and turn off after the set amount of seconds from last driver being disabled again
|
||||||
//#define CONTROLLERFAN_PIN 23 //Pin used for the fan to cool controller, comment out to disable this function
|
#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
|
||||||
#define CONTROLLERFAN_SEC 60 //How many seconds, after all motors were disabled, the fan should run
|
#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
|
||||||
|
#define CONTROLLERFAN_SPEED 255 // == full speed
|
||||||
|
|
||||||
// When first starting the main fan, run it at full speed for the
|
// When first starting the main fan, run it at full speed for the
|
||||||
// given number of milliseconds. This gets the fan spinning reliably
|
// given number of milliseconds. This gets the fan spinning reliably
|
||||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||||
//#define FAN_KICKSTART_TIME 100
|
//#define FAN_KICKSTART_TIME 100
|
||||||
|
|
||||||
|
// Extruder cooling fans
|
||||||
|
// Configure fan pin outputs to automatically turn on/off when the associated
|
||||||
|
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||||
|
// Multiple extruders can be assigned to the same pin in which case
|
||||||
|
// the fan will turn on when any selected extruder is above the threshold.
|
||||||
|
#define EXTRUDER_0_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||||
|
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||||
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================Mechanical Settings===========================
|
//=============================Mechanical Settings===========================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
// This defines the number of extruders
|
|
||||||
#define EXTRUDERS 1
|
|
||||||
|
|
||||||
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
|
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
|
||||||
|
|
||||||
|
|
||||||
|
@ -210,9 +220,9 @@
|
||||||
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
|
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
// extruder advance constant (s2/mm3)
|
// extruder advance constant (s2/mm3)
|
||||||
//
|
//
|
||||||
|
@ -276,7 +286,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#else
|
#else
|
||||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//The ASCII buffer for recieving from the serial:
|
//The ASCII buffer for recieving from the serial:
|
||||||
#define MAX_CMD_SIZE 96
|
#define MAX_CMD_SIZE 96
|
||||||
|
@ -308,6 +318,9 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Define Defines ============================
|
//============================= Define Defines ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
#if EXTRUDERS > 1 && defined TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
#error "You cannot use TEMP_SENSOR_1_AS_REDUNDANT if EXTRUDERS > 1"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_0 > 0
|
#if TEMP_SENSOR_0 > 0
|
||||||
#define THERMISTORHEATER_0 TEMP_SENSOR_0
|
#define THERMISTORHEATER_0 TEMP_SENSOR_0
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
#define START_BMPWIDTH 60 //Width in pixels
|
#define START_BMPWIDTH 60 //Width in pixels
|
||||||
#define START_BMPHEIGHT 64 //Height in pixels
|
#define START_BMPHEIGHT 64 //Height in pixels
|
||||||
#define START_BMPBYTEWIDTH 8 //Width in bytes
|
#define START_BMPBYTEWIDTH 8 //Width in bytes
|
||||||
unsigned char start_bmp[574] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char start_bmp[574] PROGMEM = { //AVR-GCC, WinAVR
|
||||||
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
|
||||||
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
|
||||||
0xFF,0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xF0,
|
0xFF,0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xF0,
|
||||||
|
@ -71,7 +71,7 @@ unsigned char start_bmp[574] PROGMEM = { //AVR-GCC, WinAVR
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
||||||
unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
||||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
|
||||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
|
||||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
|
||||||
|
@ -96,7 +96,7 @@ unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
||||||
unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
||||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
|
||||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
|
||||||
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
|
||||||
|
|
|
@ -1,12 +1,12 @@
|
||||||
# Sprinter Arduino Project Makefile
|
# Sprinter Arduino Project Makefile
|
||||||
#
|
#
|
||||||
# Makefile Based on:
|
# Makefile Based on:
|
||||||
# Arduino 0011 Makefile
|
# Arduino 0011 Makefile
|
||||||
# Arduino adaptation by mellis, eighthave, oli.keller
|
# Arduino adaptation by mellis, eighthave, oli.keller
|
||||||
# Marlin adaption by Daid
|
# Marlin adaption by Daid
|
||||||
#
|
#
|
||||||
# This has been tested with Arduino 0022.
|
# This has been tested with Arduino 0022.
|
||||||
#
|
#
|
||||||
# This makefile allows you to build sketches from the command line
|
# This makefile allows you to build sketches from the command line
|
||||||
# without the Arduino environment (or Java).
|
# without the Arduino environment (or Java).
|
||||||
#
|
#
|
||||||
|
@ -21,7 +21,7 @@
|
||||||
# (e.g. UPLOAD_PORT = /dev/tty.USB0). If the exact name of this file
|
# (e.g. UPLOAD_PORT = /dev/tty.USB0). If the exact name of this file
|
||||||
# changes, you can use * as a wildcard (e.g. UPLOAD_PORT = /dev/tty.usb*).
|
# changes, you can use * as a wildcard (e.g. UPLOAD_PORT = /dev/tty.usb*).
|
||||||
#
|
#
|
||||||
# 3. Set the line containing "MCU" to match your board's processor.
|
# 3. Set the line containing "MCU" to match your board's processor.
|
||||||
# Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
|
# Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
|
||||||
# or Diecimila have the atmega168. If you're using a LilyPad Arduino,
|
# or Diecimila have the atmega168. If you're using a LilyPad Arduino,
|
||||||
# change F_CPU to 8000000. If you are using Gen7 electronics, you
|
# change F_CPU to 8000000. If you are using Gen7 electronics, you
|
||||||
|
@ -44,7 +44,7 @@ ARDUINO_INSTALL_DIR ?= ../../arduino-0022
|
||||||
ARDUINO_VERSION ?= 22
|
ARDUINO_VERSION ?= 22
|
||||||
|
|
||||||
# You can optionally set a path to the avr-gcc tools. Requires a trailing slash. (ex: /usr/local/avr-gcc/bin)
|
# You can optionally set a path to the avr-gcc tools. Requires a trailing slash. (ex: /usr/local/avr-gcc/bin)
|
||||||
AVR_TOOLS_PATH ?=
|
AVR_TOOLS_PATH ?=
|
||||||
|
|
||||||
#Programmer configuration
|
#Programmer configuration
|
||||||
UPLOAD_RATE ?= 115200
|
UPLOAD_RATE ?= 115200
|
||||||
|
@ -213,7 +213,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
||||||
SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \
|
SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \
|
||||||
stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \
|
stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \
|
||||||
watchdog.cpp
|
watchdog.cpp
|
||||||
CXXSRC += LiquidCrystal.cpp ultralcd.cpp SPI.cpp
|
CXXSRC += LiquidCrystal.cpp ultralcd.cpp SPI.cpp Servo.cpp
|
||||||
|
|
||||||
#Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version
|
#Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version
|
||||||
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
||||||
|
@ -317,19 +317,19 @@ endif
|
||||||
# Default target.
|
# Default target.
|
||||||
all: sizeafter
|
all: sizeafter
|
||||||
|
|
||||||
build: $(BUILD_DIR) elf hex
|
build: $(BUILD_DIR) elf hex
|
||||||
|
|
||||||
# Creates the object directory
|
# Creates the object directory
|
||||||
$(BUILD_DIR):
|
$(BUILD_DIR):
|
||||||
$P mkdir -p $(BUILD_DIR)
|
$P mkdir -p $(BUILD_DIR)
|
||||||
|
|
||||||
elf: $(BUILD_DIR)/$(TARGET).elf
|
elf: $(BUILD_DIR)/$(TARGET).elf
|
||||||
hex: $(BUILD_DIR)/$(TARGET).hex
|
hex: $(BUILD_DIR)/$(TARGET).hex
|
||||||
eep: $(BUILD_DIR)/$(TARGET).eep
|
eep: $(BUILD_DIR)/$(TARGET).eep
|
||||||
lss: $(BUILD_DIR)/$(TARGET).lss
|
lss: $(BUILD_DIR)/$(TARGET).lss
|
||||||
sym: $(BUILD_DIR)/$(TARGET).sym
|
sym: $(BUILD_DIR)/$(TARGET).sym
|
||||||
|
|
||||||
# Program the device.
|
# Program the device.
|
||||||
# Do not try to reset an arduino if it's not one
|
# Do not try to reset an arduino if it's not one
|
||||||
upload: $(BUILD_DIR)/$(TARGET).hex
|
upload: $(BUILD_DIR)/$(TARGET).hex
|
||||||
ifeq (${AVRDUDE_PROGRAMMER}, arduino)
|
ifeq (${AVRDUDE_PROGRAMMER}, arduino)
|
||||||
|
@ -356,7 +356,7 @@ COFFCONVERT=$(OBJCOPY) --debugging \
|
||||||
--change-section-address .data-0x800000 \
|
--change-section-address .data-0x800000 \
|
||||||
--change-section-address .bss-0x800000 \
|
--change-section-address .bss-0x800000 \
|
||||||
--change-section-address .noinit-0x800000 \
|
--change-section-address .noinit-0x800000 \
|
||||||
--change-section-address .eeprom-0x810000
|
--change-section-address .eeprom-0x810000
|
||||||
|
|
||||||
|
|
||||||
coff: $(BUILD_DIR)/$(TARGET).elf
|
coff: $(BUILD_DIR)/$(TARGET).elf
|
||||||
|
|
|
@ -96,7 +96,7 @@ void process_commands();
|
||||||
|
|
||||||
void manage_inactivity();
|
void manage_inactivity();
|
||||||
|
|
||||||
#if X_ENABLE_PIN > -1
|
#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
|
||||||
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
||||||
#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
|
#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
|
||||||
#else
|
#else
|
||||||
|
@ -104,7 +104,7 @@ void manage_inactivity();
|
||||||
#define disable_x() ;
|
#define disable_x() ;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Y_ENABLE_PIN > -1
|
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
|
||||||
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
|
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
|
||||||
#define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
|
#define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
|
||||||
#else
|
#else
|
||||||
|
@ -112,7 +112,7 @@ void manage_inactivity();
|
||||||
#define disable_y() ;
|
#define disable_y() ;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Z_ENABLE_PIN > -1
|
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
|
||||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||||
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
|
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
|
||||||
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); }
|
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); }
|
||||||
|
@ -186,6 +186,10 @@ extern float add_homeing[3];
|
||||||
extern float min_pos[3];
|
extern float min_pos[3];
|
||||||
extern float max_pos[3];
|
extern float max_pos[3];
|
||||||
extern int fanSpeed;
|
extern int fanSpeed;
|
||||||
|
#ifdef BARICUDA
|
||||||
|
extern int ValvePressure;
|
||||||
|
extern int EtoPPressure;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef FWRETRACT
|
#ifdef FWRETRACT
|
||||||
extern bool autoretract_enabled;
|
extern bool autoretract_enabled;
|
||||||
|
|
|
@ -40,13 +40,13 @@
|
||||||
#elif defined(LCD_I2C_TYPE_MCP23017) || defined(LCD_I2C_TYPE_MCP23008)
|
#elif defined(LCD_I2C_TYPE_MCP23017) || defined(LCD_I2C_TYPE_MCP23008)
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <LiquidTWI2.h>
|
#include <LiquidTWI2.h>
|
||||||
#elif defined DOGLCD
|
#elif defined(DOGLCD)
|
||||||
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/)
|
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/)
|
||||||
#else
|
#else
|
||||||
#include <LiquidCrystal.h> // library for character LCD
|
#include <LiquidCrystal.h> // library for character LCD
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
File diff suppressed because it is too large
Load diff
341
Marlin/Servo.cpp
Normal file
341
Marlin/Servo.cpp
Normal file
|
@ -0,0 +1,341 @@
|
||||||
|
/*
|
||||||
|
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||||
|
Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||||
|
|
||||||
|
This library is free software; you can redistribute it and/or
|
||||||
|
modify it under the terms of the GNU Lesser General Public
|
||||||
|
License as published by the Free Software Foundation; either
|
||||||
|
version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
|
This library is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||||
|
Lesser General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU Lesser General Public
|
||||||
|
License along with this library; if not, write to the Free Software
|
||||||
|
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
|
||||||
|
A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
|
||||||
|
The servos are pulsed in the background using the value most recently written using the write() method
|
||||||
|
|
||||||
|
Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
|
||||||
|
Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
|
||||||
|
|
||||||
|
The methods are:
|
||||||
|
|
||||||
|
Servo - Class for manipulating servo motors connected to Arduino pins.
|
||||||
|
|
||||||
|
attach(pin ) - Attaches a servo motor to an i/o pin.
|
||||||
|
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
|
||||||
|
default min is 544, max is 2400
|
||||||
|
|
||||||
|
write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
|
||||||
|
writeMicroseconds() - Sets the servo pulse width in microseconds
|
||||||
|
read() - Gets the last written servo pulse width as an angle between 0 and 180.
|
||||||
|
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
|
||||||
|
attached() - Returns true if there is a servo attached.
|
||||||
|
detach() - Stops an attached servos from pulsing its i/o pin.
|
||||||
|
|
||||||
|
*/
|
||||||
|
#include "Configuration.h"
|
||||||
|
|
||||||
|
#ifdef NUM_SERVOS
|
||||||
|
#include <avr/interrupt.h>
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
#include "Servo.h"
|
||||||
|
|
||||||
|
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
|
||||||
|
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
|
||||||
|
|
||||||
|
|
||||||
|
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
|
||||||
|
|
||||||
|
//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER)
|
||||||
|
|
||||||
|
static servo_t servos[MAX_SERVOS]; // static array of servo structures
|
||||||
|
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
|
||||||
|
|
||||||
|
uint8_t ServoCount = 0; // the total number of attached servos
|
||||||
|
|
||||||
|
|
||||||
|
// convenience macros
|
||||||
|
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
|
||||||
|
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
|
||||||
|
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
|
||||||
|
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
|
||||||
|
|
||||||
|
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
|
||||||
|
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
|
||||||
|
|
||||||
|
/************ static functions common to all instances ***********************/
|
||||||
|
|
||||||
|
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA)
|
||||||
|
{
|
||||||
|
if( Channel[timer] < 0 )
|
||||||
|
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
|
||||||
|
else{
|
||||||
|
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true )
|
||||||
|
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
|
||||||
|
}
|
||||||
|
|
||||||
|
Channel[timer]++; // increment to the next channel
|
||||||
|
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
|
||||||
|
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
|
||||||
|
if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated
|
||||||
|
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// finished all channels so wait for the refresh period to expire before starting over
|
||||||
|
if( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed
|
||||||
|
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
|
||||||
|
else
|
||||||
|
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
|
||||||
|
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
|
||||||
|
// Interrupt handlers for Arduino
|
||||||
|
#if defined(_useTimer1)
|
||||||
|
SIGNAL (TIMER1_COMPA_vect)
|
||||||
|
{
|
||||||
|
handle_interrupts(_timer1, &TCNT1, &OCR1A);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_useTimer3)
|
||||||
|
SIGNAL (TIMER3_COMPA_vect)
|
||||||
|
{
|
||||||
|
handle_interrupts(_timer3, &TCNT3, &OCR3A);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_useTimer4)
|
||||||
|
SIGNAL (TIMER4_COMPA_vect)
|
||||||
|
{
|
||||||
|
handle_interrupts(_timer4, &TCNT4, &OCR4A);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_useTimer5)
|
||||||
|
SIGNAL (TIMER5_COMPA_vect)
|
||||||
|
{
|
||||||
|
handle_interrupts(_timer5, &TCNT5, &OCR5A);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#elif defined WIRING
|
||||||
|
// Interrupt handlers for Wiring
|
||||||
|
#if defined(_useTimer1)
|
||||||
|
void Timer1Service()
|
||||||
|
{
|
||||||
|
handle_interrupts(_timer1, &TCNT1, &OCR1A);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if defined(_useTimer3)
|
||||||
|
void Timer3Service()
|
||||||
|
{
|
||||||
|
handle_interrupts(_timer3, &TCNT3, &OCR3A);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
static void initISR(timer16_Sequence_t timer)
|
||||||
|
{
|
||||||
|
#if defined (_useTimer1)
|
||||||
|
if(timer == _timer1) {
|
||||||
|
TCCR1A = 0; // normal counting mode
|
||||||
|
TCCR1B = _BV(CS11); // set prescaler of 8
|
||||||
|
TCNT1 = 0; // clear the timer count
|
||||||
|
#if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__)
|
||||||
|
TIFR |= _BV(OCF1A); // clear any pending interrupts;
|
||||||
|
TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt
|
||||||
|
#else
|
||||||
|
// here if not ATmega8 or ATmega128
|
||||||
|
TIFR1 |= _BV(OCF1A); // clear any pending interrupts;
|
||||||
|
TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt
|
||||||
|
#endif
|
||||||
|
#if defined(WIRING)
|
||||||
|
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined (_useTimer3)
|
||||||
|
if(timer == _timer3) {
|
||||||
|
TCCR3A = 0; // normal counting mode
|
||||||
|
TCCR3B = _BV(CS31); // set prescaler of 8
|
||||||
|
TCNT3 = 0; // clear the timer count
|
||||||
|
#if defined(__AVR_ATmega128__)
|
||||||
|
TIFR |= _BV(OCF3A); // clear any pending interrupts;
|
||||||
|
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
|
||||||
|
#else
|
||||||
|
TIFR3 = _BV(OCF3A); // clear any pending interrupts;
|
||||||
|
TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt
|
||||||
|
#endif
|
||||||
|
#if defined(WIRING)
|
||||||
|
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined (_useTimer4)
|
||||||
|
if(timer == _timer4) {
|
||||||
|
TCCR4A = 0; // normal counting mode
|
||||||
|
TCCR4B = _BV(CS41); // set prescaler of 8
|
||||||
|
TCNT4 = 0; // clear the timer count
|
||||||
|
TIFR4 = _BV(OCF4A); // clear any pending interrupts;
|
||||||
|
TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined (_useTimer5)
|
||||||
|
if(timer == _timer5) {
|
||||||
|
TCCR5A = 0; // normal counting mode
|
||||||
|
TCCR5B = _BV(CS51); // set prescaler of 8
|
||||||
|
TCNT5 = 0; // clear the timer count
|
||||||
|
TIFR5 = _BV(OCF5A); // clear any pending interrupts;
|
||||||
|
TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void finISR(timer16_Sequence_t timer)
|
||||||
|
{
|
||||||
|
//disable use of the given timer
|
||||||
|
#if defined WIRING // Wiring
|
||||||
|
if(timer == _timer1) {
|
||||||
|
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
|
||||||
|
TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
|
||||||
|
#else
|
||||||
|
TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
|
||||||
|
#endif
|
||||||
|
timerDetach(TIMER1OUTCOMPAREA_INT);
|
||||||
|
}
|
||||||
|
else if(timer == _timer3) {
|
||||||
|
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
|
||||||
|
TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
|
||||||
|
#else
|
||||||
|
ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
|
||||||
|
#endif
|
||||||
|
timerDetach(TIMER3OUTCOMPAREA_INT);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
//For arduino - in future: call here to a currently undefined function to reset the timer
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static boolean isTimerActive(timer16_Sequence_t timer)
|
||||||
|
{
|
||||||
|
// returns true if any servo is active on this timer
|
||||||
|
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
|
||||||
|
if(SERVO(timer,channel).Pin.isActive == true)
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/****************** end of static functions ******************************/
|
||||||
|
|
||||||
|
Servo::Servo()
|
||||||
|
{
|
||||||
|
if( ServoCount < MAX_SERVOS) {
|
||||||
|
this->servoIndex = ServoCount++; // assign a servo index to this instance
|
||||||
|
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
|
||||||
|
}
|
||||||
|
else
|
||||||
|
this->servoIndex = INVALID_SERVO ; // too many servos
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Servo::attach(int pin)
|
||||||
|
{
|
||||||
|
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Servo::attach(int pin, int min, int max)
|
||||||
|
{
|
||||||
|
if(this->servoIndex < MAX_SERVOS ) {
|
||||||
|
pinMode( pin, OUTPUT) ; // set servo pin to output
|
||||||
|
servos[this->servoIndex].Pin.nbr = pin;
|
||||||
|
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
|
||||||
|
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
|
||||||
|
this->max = (MAX_PULSE_WIDTH - max)/4;
|
||||||
|
// initialize the timer if it has not already been initialized
|
||||||
|
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
|
||||||
|
if(isTimerActive(timer) == false)
|
||||||
|
initISR(timer);
|
||||||
|
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
|
||||||
|
}
|
||||||
|
return this->servoIndex ;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Servo::detach()
|
||||||
|
{
|
||||||
|
servos[this->servoIndex].Pin.isActive = false;
|
||||||
|
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
|
||||||
|
if(isTimerActive(timer) == false) {
|
||||||
|
finISR(timer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Servo::write(int value)
|
||||||
|
{
|
||||||
|
if(value < MIN_PULSE_WIDTH)
|
||||||
|
{ // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
|
||||||
|
if(value < 0) value = 0;
|
||||||
|
if(value > 180) value = 180;
|
||||||
|
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
|
||||||
|
}
|
||||||
|
this->writeMicroseconds(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Servo::writeMicroseconds(int value)
|
||||||
|
{
|
||||||
|
// calculate and store the values for the given channel
|
||||||
|
byte channel = this->servoIndex;
|
||||||
|
if( (channel < MAX_SERVOS) ) // ensure channel is valid
|
||||||
|
{
|
||||||
|
if( value < SERVO_MIN() ) // ensure pulse width is valid
|
||||||
|
value = SERVO_MIN();
|
||||||
|
else if( value > SERVO_MAX() )
|
||||||
|
value = SERVO_MAX();
|
||||||
|
|
||||||
|
value = value - TRIM_DURATION;
|
||||||
|
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
|
||||||
|
|
||||||
|
uint8_t oldSREG = SREG;
|
||||||
|
cli();
|
||||||
|
servos[channel].ticks = value;
|
||||||
|
SREG = oldSREG;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Servo::read() // return the value as degrees
|
||||||
|
{
|
||||||
|
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
|
||||||
|
}
|
||||||
|
|
||||||
|
int Servo::readMicroseconds()
|
||||||
|
{
|
||||||
|
unsigned int pulsewidth;
|
||||||
|
if( this->servoIndex != INVALID_SERVO )
|
||||||
|
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009
|
||||||
|
else
|
||||||
|
pulsewidth = 0;
|
||||||
|
|
||||||
|
return pulsewidth;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Servo::attached()
|
||||||
|
{
|
||||||
|
return servos[this->servoIndex].Pin.isActive ;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
132
Marlin/Servo.h
Normal file
132
Marlin/Servo.h
Normal file
|
@ -0,0 +1,132 @@
|
||||||
|
/*
|
||||||
|
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
|
||||||
|
Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||||
|
|
||||||
|
This library is free software; you can redistribute it and/or
|
||||||
|
modify it under the terms of the GNU Lesser General Public
|
||||||
|
License as published by the Free Software Foundation; either
|
||||||
|
version 2.1 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
|
This library is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||||
|
Lesser General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU Lesser General Public
|
||||||
|
License along with this library; if not, write to the Free Software
|
||||||
|
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
|
||||||
|
A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
|
||||||
|
The servos are pulsed in the background using the value most recently written using the write() method
|
||||||
|
|
||||||
|
Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
|
||||||
|
Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
|
||||||
|
The sequence used to sieze timers is defined in timers.h
|
||||||
|
|
||||||
|
The methods are:
|
||||||
|
|
||||||
|
Servo - Class for manipulating servo motors connected to Arduino pins.
|
||||||
|
|
||||||
|
attach(pin ) - Attaches a servo motor to an i/o pin.
|
||||||
|
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
|
||||||
|
default min is 544, max is 2400
|
||||||
|
|
||||||
|
write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
|
||||||
|
writeMicroseconds() - Sets the servo pulse width in microseconds
|
||||||
|
read() - Gets the last written servo pulse width as an angle between 0 and 180.
|
||||||
|
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
|
||||||
|
attached() - Returns true if there is a servo attached.
|
||||||
|
detach() - Stops an attached servos from pulsing its i/o pin.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef Servo_h
|
||||||
|
#define Servo_h
|
||||||
|
|
||||||
|
#include <inttypes.h>
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Defines for 16 bit timers used with Servo library
|
||||||
|
*
|
||||||
|
* If _useTimerX is defined then TimerX is a 16 bit timer on the curent board
|
||||||
|
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
|
||||||
|
* _Nbr_16timers indicates how many 16 bit timers are available.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Say which 16 bit timers can be used and in what order
|
||||||
|
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||||
|
#define _useTimer5
|
||||||
|
//#define _useTimer1
|
||||||
|
#define _useTimer3
|
||||||
|
#define _useTimer4
|
||||||
|
//typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
typedef enum { _timer5, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega32U4__)
|
||||||
|
//#define _useTimer1
|
||||||
|
#define _useTimer3
|
||||||
|
//typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
|
||||||
|
#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
|
||||||
|
#define _useTimer3
|
||||||
|
//#define _useTimer1
|
||||||
|
//typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
|
||||||
|
#define _useTimer3
|
||||||
|
//#define _useTimer1
|
||||||
|
//typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
typedef enum { _timer3, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
|
||||||
|
#else // everything else
|
||||||
|
//#define _useTimer1
|
||||||
|
//typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
typedef enum { _Nbr_16timers } timer16_Sequence_t ;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define Servo_VERSION 2 // software version of this library
|
||||||
|
|
||||||
|
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
|
||||||
|
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
|
||||||
|
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
|
||||||
|
#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds
|
||||||
|
|
||||||
|
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
|
||||||
|
#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER)
|
||||||
|
|
||||||
|
#define INVALID_SERVO 255 // flag indicating an invalid servo index
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint8_t nbr :6 ; // a pin number from 0 to 63
|
||||||
|
uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false
|
||||||
|
} ServoPin_t ;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
ServoPin_t Pin;
|
||||||
|
unsigned int ticks;
|
||||||
|
} servo_t;
|
||||||
|
|
||||||
|
class Servo
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
Servo();
|
||||||
|
uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
|
||||||
|
uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
|
||||||
|
void detach();
|
||||||
|
void write(int value); // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds
|
||||||
|
void writeMicroseconds(int value); // Write pulse width in microseconds
|
||||||
|
int read(); // returns current pulse width as an angle between 0 and 180 degrees
|
||||||
|
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
|
||||||
|
bool attached(); // return true if this servo is attached, otherwise false
|
||||||
|
private:
|
||||||
|
uint8_t servoIndex; // index into the channel data for this servo
|
||||||
|
int8_t min; // minimum is this value times 4 added to MIN_PULSE_WIDTH
|
||||||
|
int8_t max; // maximum is this value times 4 added to MAX_PULSE_WIDTH
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
|
@ -19,12 +19,25 @@
|
||||||
* 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
|
||||||
|
#define BLEN_A 0
|
||||||
|
#define BLEN_B 1
|
||||||
|
#define BLEN_C 2
|
||||||
|
#define EN_A (1<<BLEN_A)
|
||||||
|
#define EN_B (1<<BLEN_B)
|
||||||
|
#define EN_C (1<<BLEN_C)
|
||||||
|
#define encrot0 0
|
||||||
|
#define encrot1 2
|
||||||
|
#define encrot2 3
|
||||||
|
#define encrot3 1
|
||||||
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
|
#endif
|
||||||
|
|
||||||
// CHANGE_DE begin ***
|
#include <U8glib.h>
|
||||||
#include <U8glib.h> // DE_U8glib
|
|
||||||
#include "DOGMbitmaps.h"
|
#include "DOGMbitmaps.h"
|
||||||
#include "dogm_font_data_marlin.h"
|
#include "dogm_font_data_marlin.h"
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
|
#include "ultralcd_st7920_u8glib_rrd.h"
|
||||||
|
|
||||||
|
|
||||||
/* Russian language not supported yet, needs custom font
|
/* Russian language not supported yet, needs custom font
|
||||||
|
@ -61,11 +74,10 @@
|
||||||
|
|
||||||
#define FONT_STATUSMENU u8g_font_6x9
|
#define FONT_STATUSMENU u8g_font_6x9
|
||||||
|
|
||||||
|
|
||||||
// LCD selection
|
// LCD selection
|
||||||
#ifdef U8GLIB_ST7920
|
#ifdef U8GLIB_ST7920
|
||||||
// SPI Com: SCK = en = (D4), MOSI = rw = (RS), CS = di = (ENABLE)
|
//U8GLIB_ST7920_128X64_RRD u8g(0,0,0);
|
||||||
U8GLIB_ST7920_128X64_1X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS);
|
U8GLIB_ST7920_128X64_RRD u8g(0);
|
||||||
#else
|
#else
|
||||||
U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0
|
U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0
|
||||||
#endif
|
#endif
|
||||||
|
@ -88,11 +100,11 @@ static void lcd_implementation_init()
|
||||||
u8g.setRot90(); // Rotate screen by 90°
|
u8g.setRot90(); // Rotate screen by 90°
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef LCD_SCREEN_ROT_180;
|
#ifdef LCD_SCREEN_ROT_180
|
||||||
u8g.setRot180(); // Rotate screen by 180°
|
u8g.setRot180(); // Rotate screen by 180°
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef LCD_SCREEN_ROT_270;
|
#ifdef LCD_SCREEN_ROT_270
|
||||||
u8g.setRot270(); // Rotate screen by 270°
|
u8g.setRot270(); // Rotate screen by 270°
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -266,7 +278,7 @@ static void lcd_implementation_status_screen()
|
||||||
// Fan
|
// Fan
|
||||||
u8g.setFont(FONT_STATUSMENU);
|
u8g.setFont(FONT_STATUSMENU);
|
||||||
u8g.setPrintPos(104,27);
|
u8g.setPrintPos(104,27);
|
||||||
#if FAN_PIN > 0
|
#if defined(FAN_PIN) && FAN_PIN > -1
|
||||||
u8g.print(itostr3(int((fanSpeed*100)/256 + 1)));
|
u8g.print(itostr3(int((fanSpeed*100)/256 + 1)));
|
||||||
u8g.print("%");
|
u8g.print("%");
|
||||||
#else
|
#else
|
||||||
|
|
696
Marlin/fastio.h
696
Marlin/fastio.h
|
@ -2575,8 +2575,702 @@ pins
|
||||||
#define PF7_DDR DDRF
|
#define PF7_DDR DDRF
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#if defined (__AVR_ATmega1281__) || defined (__AVR_ATmega2561__)
|
||||||
|
// UART
|
||||||
|
#define RXD DIO0
|
||||||
|
#define TXD DIO1
|
||||||
|
|
||||||
|
// SPI
|
||||||
|
#define SCK DIO10
|
||||||
|
#define MISO DIO12
|
||||||
|
#define MOSI DIO11
|
||||||
|
#define SS DIO16
|
||||||
|
|
||||||
|
// TWI (I2C)
|
||||||
|
#define SCL DIO17
|
||||||
|
#define SDA DIO18
|
||||||
|
|
||||||
|
// timers and PWM
|
||||||
|
#define OC0A DIO9
|
||||||
|
#define OC0B DIO4
|
||||||
|
#define OC1A DIO7
|
||||||
|
#define OC1B DIO8
|
||||||
|
#define OC2A DIO6
|
||||||
|
#define OC3A DIO5
|
||||||
|
#define OC3B DIO2
|
||||||
|
#define OC3C DIO3
|
||||||
|
|
||||||
|
|
||||||
|
// change for your board
|
||||||
|
#define DEBUG_LED DIO46
|
||||||
|
|
||||||
|
/*
|
||||||
|
pins
|
||||||
|
*/
|
||||||
|
#define DIO0_PIN PINE0
|
||||||
|
#define DIO0_RPORT PINE
|
||||||
|
#define DIO0_WPORT PORTE
|
||||||
|
#define DIO0_DDR DDRE
|
||||||
|
#define DIO0_PWM NULL
|
||||||
|
|
||||||
|
#define DIO1_PIN PINE1
|
||||||
|
#define DIO1_RPORT PINE
|
||||||
|
#define DIO1_WPORT PORTE
|
||||||
|
#define DIO1_DDR DDRE
|
||||||
|
#define DIO1_PWM NULL
|
||||||
|
|
||||||
|
#define DIO2_PIN PINE4
|
||||||
|
#define DIO2_RPORT PINE
|
||||||
|
#define DIO2_WPORT PORTE
|
||||||
|
#define DIO2_DDR DDRE
|
||||||
|
#define DIO2_PWM &OCR3BL
|
||||||
|
|
||||||
|
#define DIO3_PIN PINE5
|
||||||
|
#define DIO3_RPORT PINE
|
||||||
|
#define DIO3_WPORT PORTE
|
||||||
|
#define DIO3_DDR DDRE
|
||||||
|
#define DIO3_PWM &OCR3CL
|
||||||
|
|
||||||
|
#define DIO4_PIN PING5
|
||||||
|
#define DIO4_RPORT PING
|
||||||
|
#define DIO4_WPORT PORTG
|
||||||
|
#define DIO4_DDR DDRG
|
||||||
|
#define DIO4_PWM &OCR0B
|
||||||
|
|
||||||
|
#define DIO5_PIN PINE3
|
||||||
|
#define DIO5_RPORT PINE
|
||||||
|
#define DIO5_WPORT PORTE
|
||||||
|
#define DIO5_DDR DDRE
|
||||||
|
#define DIO5_PWM &OCR3AL
|
||||||
|
|
||||||
|
#define DIO6_PIN PINB4
|
||||||
|
#define DIO6_RPORT PINB
|
||||||
|
#define DIO6_WPORT PORTB
|
||||||
|
#define DIO6_DDR DDRB
|
||||||
|
#define DIO6_PWM &OCR2AL
|
||||||
|
|
||||||
|
#define DIO7_PIN PINB5
|
||||||
|
#define DIO7_RPORT PINB
|
||||||
|
#define DIO7_WPORT PORTB
|
||||||
|
#define DIO7_DDR DDRB
|
||||||
|
#define DIO7_PWM &OCR1AL
|
||||||
|
|
||||||
|
#define DIO8_PIN PINB6
|
||||||
|
#define DIO8_RPORT PINB
|
||||||
|
#define DIO8_WPORT PORTB
|
||||||
|
#define DIO8_DDR DDRB
|
||||||
|
#define DIO8_PWM &OCR1BL
|
||||||
|
|
||||||
|
#define DIO9_PIN PINB7
|
||||||
|
#define DIO9_RPORT PINB
|
||||||
|
#define DIO9_WPORT PORTB
|
||||||
|
#define DIO9_DDR DDRB
|
||||||
|
#define DIO9_PWM &OCR0AL
|
||||||
|
|
||||||
|
#define DIO10_PIN PINB1
|
||||||
|
#define DIO10_RPORT PINB
|
||||||
|
#define DIO10_WPORT PORTB
|
||||||
|
#define DIO10_DDR DDRB
|
||||||
|
#define DIO10_PWM NULL
|
||||||
|
|
||||||
|
#define DIO11_PIN PINB2
|
||||||
|
#define DIO11_RPORT PINB
|
||||||
|
#define DIO11_WPORT PORTB
|
||||||
|
#define DIO11_DDR DDRB
|
||||||
|
#define DIO11_PWM NULL
|
||||||
|
|
||||||
|
#define DIO12_PIN PINB3
|
||||||
|
#define DIO12_RPORT PINB
|
||||||
|
#define DIO12_WPORT PORTB
|
||||||
|
#define DIO12_DDR DDRB
|
||||||
|
#define DIO12_PWM NULL
|
||||||
|
|
||||||
|
#define DIO13_PIN PINE2
|
||||||
|
#define DIO13_RPORT PINE
|
||||||
|
#define DIO13_WPORT PORTE
|
||||||
|
#define DIO13_DDR DDRE
|
||||||
|
#define DIO13_PWM NULL
|
||||||
|
|
||||||
|
#define DIO14_PIN PINE6
|
||||||
|
#define DIO14_RPORT PINE
|
||||||
|
#define DIO14_WPORT PORTE
|
||||||
|
#define DIO14_DDR DDRE
|
||||||
|
#define DIO14_PWM NULL
|
||||||
|
|
||||||
|
#define DIO15_PIN PINE7
|
||||||
|
#define DIO15_RPORT PINE
|
||||||
|
#define DIO15_WPORT PORTE
|
||||||
|
#define DIO15_DDR DDRE
|
||||||
|
#define DIO15_PWM NULL
|
||||||
|
|
||||||
|
#define DIO16_PIN PINB0
|
||||||
|
#define DIO16_RPORT PINB
|
||||||
|
#define DIO16_WPORT PORTB
|
||||||
|
#define DIO16_DDR DDRB
|
||||||
|
#define DIO16_PWM NULL
|
||||||
|
|
||||||
|
#define DIO17_PIN PIND0
|
||||||
|
#define DIO17_RPORT PIND
|
||||||
|
#define DIO17_WPORT PORTD
|
||||||
|
#define DIO17_DDR DDRD
|
||||||
|
#define DIO17_PWM NULL
|
||||||
|
|
||||||
|
#define DIO18_PIN PIND1
|
||||||
|
#define DIO18_RPORT PIND
|
||||||
|
#define DIO18_WPORT PORTD
|
||||||
|
#define DIO18_DDR DDRD
|
||||||
|
#define DIO18_PWM NULL
|
||||||
|
|
||||||
|
#define DIO19_PIN PIND2
|
||||||
|
#define DIO19_RPORT PIND
|
||||||
|
#define DIO19_WPORT PORTD
|
||||||
|
#define DIO19_DDR DDRD
|
||||||
|
#define DIO19_PWM NULL
|
||||||
|
|
||||||
|
#define DIO20_PIN PIND3
|
||||||
|
#define DIO20_RPORT PIND
|
||||||
|
#define DIO20_WPORT PORTD
|
||||||
|
#define DIO20_DDR DDRD
|
||||||
|
#define DIO20_PWM NULL
|
||||||
|
|
||||||
|
#define DIO21_PIN PIND4
|
||||||
|
#define DIO21_RPORT PIND
|
||||||
|
#define DIO21_WPORT PORTD
|
||||||
|
#define DIO21_DDR DDRD
|
||||||
|
#define DIO21_PWM NULL
|
||||||
|
|
||||||
|
#define DIO22_PIN PIND5
|
||||||
|
#define DIO22_RPORT PIND
|
||||||
|
#define DIO22_WPORT PORTD
|
||||||
|
#define DIO22_DDR DDRD
|
||||||
|
#define DIO22_PWM NULL
|
||||||
|
|
||||||
|
#define DIO23_PIN PIND6
|
||||||
|
#define DIO23_RPORT PIND
|
||||||
|
#define DIO23_WPORT PORTD
|
||||||
|
#define DIO23_DDR DDRD
|
||||||
|
#define DIO23_PWM NULL
|
||||||
|
|
||||||
|
#define DIO24_PIN PIND7
|
||||||
|
#define DIO24_RPORT PIND
|
||||||
|
#define DIO24_WPORT PORTD
|
||||||
|
#define DIO24_DDR DDRD
|
||||||
|
#define DIO24_PWM NULL
|
||||||
|
|
||||||
|
#define DIO25_PIN PING0
|
||||||
|
#define DIO25_RPORT PING
|
||||||
|
#define DIO25_WPORT PORTG
|
||||||
|
#define DIO25_DDR DDRG
|
||||||
|
#define DIO25_PWM NULL
|
||||||
|
|
||||||
|
#define DIO26_PIN PING1
|
||||||
|
#define DIO26_RPORT PING
|
||||||
|
#define DIO26_WPORT PORTG
|
||||||
|
#define DIO26_DDR DDRG
|
||||||
|
#define DIO26_PWM NULL
|
||||||
|
|
||||||
|
#define DIO27_PIN PING2
|
||||||
|
#define DIO27_RPORT PING
|
||||||
|
#define DIO27_WPORT PORTG
|
||||||
|
#define DIO27_DDR DDRG
|
||||||
|
#define DIO27_PWM NULL
|
||||||
|
|
||||||
|
#define DIO28_PIN PING3
|
||||||
|
#define DIO28_RPORT PING
|
||||||
|
#define DIO28_WPORT PORTG
|
||||||
|
#define DIO28_DDR DDRG
|
||||||
|
#define DIO28_PWM NULL
|
||||||
|
|
||||||
|
#define DIO29_PIN PING4
|
||||||
|
#define DIO29_RPORT PING
|
||||||
|
#define DIO29_WPORT PORTG
|
||||||
|
#define DIO29_DDR DDRG
|
||||||
|
#define DIO29_PWM NULL
|
||||||
|
|
||||||
|
#define DIO30_PIN PINC0
|
||||||
|
#define DIO30_RPORT PINC
|
||||||
|
#define DIO30_WPORT PORTC
|
||||||
|
#define DIO30_DDR DDRC
|
||||||
|
#define DIO30_PWM NULL
|
||||||
|
|
||||||
|
#define DIO31_PIN PINC1
|
||||||
|
#define DIO31_RPORT PINC
|
||||||
|
#define DIO31_WPORT PORTC
|
||||||
|
#define DIO31_DDR DDRC
|
||||||
|
#define DIO31_PWM NULL
|
||||||
|
|
||||||
|
#define DIO32_PIN PINC2
|
||||||
|
#define DIO32_RPORT PINC
|
||||||
|
#define DIO32_WPORT PORTC
|
||||||
|
#define DIO32_DDR DDRC
|
||||||
|
#define DIO32_PWM NULL
|
||||||
|
|
||||||
|
#define DIO33_PIN PINC3
|
||||||
|
#define DIO33_RPORT PINC
|
||||||
|
#define DIO33_WPORT PORTC
|
||||||
|
#define DIO33_DDR DDRC
|
||||||
|
#define DIO33_PWM NULL
|
||||||
|
|
||||||
|
#define DIO34_PIN PINC4
|
||||||
|
#define DIO34_RPORT PINC
|
||||||
|
#define DIO34_WPORT PORTC
|
||||||
|
#define DIO34_DDR DDRC
|
||||||
|
#define DIO34_PWM NULL
|
||||||
|
|
||||||
|
#define DIO35_PIN PINC5
|
||||||
|
#define DIO35_RPORT PINC
|
||||||
|
#define DIO35_WPORT PORTC
|
||||||
|
#define DIO35_DDR DDRC
|
||||||
|
#define DIO35_PWM NULL
|
||||||
|
|
||||||
|
#define DIO36_PIN PINC6
|
||||||
|
#define DIO36_RPORT PINC
|
||||||
|
#define DIO36_WPORT PORTC
|
||||||
|
#define DIO36_DDR DDRC
|
||||||
|
#define DIO36_PWM NULL
|
||||||
|
|
||||||
|
#define DIO37_PIN PINC7
|
||||||
|
#define DIO37_RPORT PINC
|
||||||
|
#define DIO37_WPORT PORTC
|
||||||
|
#define DIO37_DDR DDRC
|
||||||
|
#define DIO37_PWM NULL
|
||||||
|
|
||||||
|
#define DIO38_PIN PINA0
|
||||||
|
#define DIO38_RPORT PINA
|
||||||
|
#define DIO38_WPORT PORTA
|
||||||
|
#define DIO38_DDR DDRA
|
||||||
|
#define DIO38_PWM NULL
|
||||||
|
|
||||||
|
#define DIO39_PIN PINA1
|
||||||
|
#define DIO39_RPORT PINA
|
||||||
|
#define DIO39_WPORT PORTA
|
||||||
|
#define DIO39_DDR DDRA
|
||||||
|
#define DIO39_PWM NULL
|
||||||
|
|
||||||
|
#define DIO40_PIN PINA2
|
||||||
|
#define DIO40_RPORT PINA
|
||||||
|
#define DIO40_WPORT PORTA
|
||||||
|
#define DIO40_DDR DDRA
|
||||||
|
#define DIO40_PWM NULL
|
||||||
|
|
||||||
|
#define DIO41_PIN PINA3
|
||||||
|
#define DIO41_RPORT PINA
|
||||||
|
#define DIO41_WPORT PORTA
|
||||||
|
#define DIO41_DDR DDRA
|
||||||
|
#define DIO41_PWM NULL
|
||||||
|
|
||||||
|
#define DIO42_PIN PINA4
|
||||||
|
#define DIO42_RPORT PINA
|
||||||
|
#define DIO42_WPORT PORTA
|
||||||
|
#define DIO42_DDR DDRA
|
||||||
|
#define DIO42_PWM NULL
|
||||||
|
|
||||||
|
#define DIO43_PIN PINA5
|
||||||
|
#define DIO43_RPORT PINA
|
||||||
|
#define DIO43_WPORT PORTA
|
||||||
|
#define DIO43_DDR DDRA
|
||||||
|
#define DIO43_PWM NULL
|
||||||
|
|
||||||
|
#define DIO44_PIN PINA6
|
||||||
|
#define DIO44_RPORT PINA
|
||||||
|
#define DIO44_WPORT PORTA
|
||||||
|
#define DIO44_DDR DDRA
|
||||||
|
#define DIO44_PWM NULL
|
||||||
|
|
||||||
|
#define DIO45_PIN PINA7
|
||||||
|
#define DIO45_RPORT PINA
|
||||||
|
#define DIO45_WPORT PORTA
|
||||||
|
#define DIO45_DDR DDRA
|
||||||
|
#define DIO45_PWM NULL
|
||||||
|
|
||||||
|
#define DIO46_PIN PINF0
|
||||||
|
#define DIO46_RPORT PINF
|
||||||
|
#define DIO46_WPORT PORTF
|
||||||
|
#define DIO46_DDR DDRF
|
||||||
|
#define DIO46_PWM NULL
|
||||||
|
|
||||||
|
#define DIO47_PIN PINF1
|
||||||
|
#define DIO47_RPORT PINF
|
||||||
|
#define DIO47_WPORT PORTF
|
||||||
|
#define DIO47_DDR DDRF
|
||||||
|
#define DIO47_PWM NULL
|
||||||
|
|
||||||
|
#define DIO48_PIN PINF2
|
||||||
|
#define DIO48_RPORT PINF
|
||||||
|
#define DIO48_WPORT PORTF
|
||||||
|
#define DIO48_DDR DDRF
|
||||||
|
#define DIO48_PWM NULL
|
||||||
|
|
||||||
|
#define DIO49_PIN PINF3
|
||||||
|
#define DIO49_RPORT PINF
|
||||||
|
#define DIO49_WPORT PORTF
|
||||||
|
#define DIO49_DDR DDRF
|
||||||
|
#define DIO49_PWM NULL
|
||||||
|
|
||||||
|
#define DIO50_PIN PINF4
|
||||||
|
#define DIO50_RPORT PINF
|
||||||
|
#define DIO50_WPORT PORTF
|
||||||
|
#define DIO50_DDR DDRF
|
||||||
|
#define DIO50_PWM NULL
|
||||||
|
|
||||||
|
#define DIO51_PIN PINF5
|
||||||
|
#define DIO51_RPORT PINF
|
||||||
|
#define DIO51_WPORT PORTF
|
||||||
|
#define DIO51_DDR DDRF
|
||||||
|
#define DIO51_PWM NULL
|
||||||
|
|
||||||
|
#define DIO52_PIN PINF6
|
||||||
|
#define DIO52_RPORT PINF
|
||||||
|
#define DIO52_WPORT PORTF
|
||||||
|
#define DIO52_DDR DDRF
|
||||||
|
#define DIO52_PWM NULL
|
||||||
|
|
||||||
|
#define DIO53_PIN PINF7
|
||||||
|
#define DIO53_RPORT PINF
|
||||||
|
#define DIO53_WPORT PORTF
|
||||||
|
#define DIO53_DDR DDRF
|
||||||
|
#define DIO53_PWM NULL
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#undef PA0
|
||||||
|
#define PA0_PIN PINA0
|
||||||
|
#define PA0_RPORT PINA
|
||||||
|
#define PA0_WPORT PORTA
|
||||||
|
#define PA0_DDR DDRA
|
||||||
|
#define PA0_PWM NULL
|
||||||
|
#undef PA1
|
||||||
|
#define PA1_PIN PINA1
|
||||||
|
#define PA1_RPORT PINA
|
||||||
|
#define PA1_WPORT PORTA
|
||||||
|
#define PA1_DDR DDRA
|
||||||
|
#define PA1_PWM NULL
|
||||||
|
#undef PA2
|
||||||
|
#define PA2_PIN PINA2
|
||||||
|
#define PA2_RPORT PINA
|
||||||
|
#define PA2_WPORT PORTA
|
||||||
|
#define PA2_DDR DDRA
|
||||||
|
#define PA2_PWM NULL
|
||||||
|
#undef PA3
|
||||||
|
#define PA3_PIN PINA3
|
||||||
|
#define PA3_RPORT PINA
|
||||||
|
#define PA3_WPORT PORTA
|
||||||
|
#define PA3_DDR DDRA
|
||||||
|
#define PA3_PWM NULL
|
||||||
|
#undef PA4
|
||||||
|
#define PA4_PIN PINA4
|
||||||
|
#define PA4_RPORT PINA
|
||||||
|
#define PA4_WPORT PORTA
|
||||||
|
#define PA4_DDR DDRA
|
||||||
|
#define PA4_PWM NULL
|
||||||
|
#undef PA5
|
||||||
|
#define PA5_PIN PINA5
|
||||||
|
#define PA5_RPORT PINA
|
||||||
|
#define PA5_WPORT PORTA
|
||||||
|
#define PA5_DDR DDRA
|
||||||
|
#define PA5_PWM NULL
|
||||||
|
#undef PA6
|
||||||
|
#define PA6_PIN PINA6
|
||||||
|
#define PA6_RPORT PINA
|
||||||
|
#define PA6_WPORT PORTA
|
||||||
|
#define PA6_DDR DDRA
|
||||||
|
#define PA6_PWM NULL
|
||||||
|
#undef PA7
|
||||||
|
#define PA7_PIN PINA7
|
||||||
|
#define PA7_RPORT PINA
|
||||||
|
#define PA7_WPORT PORTA
|
||||||
|
#define PA7_DDR DDRA
|
||||||
|
#define PA7_PWM NULL
|
||||||
|
|
||||||
|
#undef PB0
|
||||||
|
#define PB0_PIN PINB0
|
||||||
|
#define PB0_RPORT PINB
|
||||||
|
#define PB0_WPORT PORTB
|
||||||
|
#define PB0_DDR DDRB
|
||||||
|
#define PB0_PWM NULL
|
||||||
|
#undef PB1
|
||||||
|
#define PB1_PIN PINB1
|
||||||
|
#define PB1_RPORT PINB
|
||||||
|
#define PB1_WPORT PORTB
|
||||||
|
#define PB1_DDR DDRB
|
||||||
|
#define PB1_PWM NULL
|
||||||
|
#undef PB2
|
||||||
|
#define PB2_PIN PINB2
|
||||||
|
#define PB2_RPORT PINB
|
||||||
|
#define PB2_WPORT PORTB
|
||||||
|
#define PB2_DDR DDRB
|
||||||
|
#define PB2_PWM NULL
|
||||||
|
#undef PB3
|
||||||
|
#define PB3_PIN PINB3
|
||||||
|
#define PB3_RPORT PINB
|
||||||
|
#define PB3_WPORT PORTB
|
||||||
|
#define PB3_DDR DDRB
|
||||||
|
#define PB3_PWM NULL
|
||||||
|
#undef PB4
|
||||||
|
#define PB4_PIN PINB4
|
||||||
|
#define PB4_RPORT PINB
|
||||||
|
#define PB4_WPORT PORTB
|
||||||
|
#define PB4_DDR DDRB
|
||||||
|
#define PB4_PWM &OCR2A
|
||||||
|
#undef PB5
|
||||||
|
#define PB5_PIN PINB5
|
||||||
|
#define PB5_RPORT PINB
|
||||||
|
#define PB5_WPORT PORTB
|
||||||
|
#define PB5_DDR DDRB
|
||||||
|
#define PB5_PWM NULL
|
||||||
|
#undef PB6
|
||||||
|
#define PB6_PIN PINB6
|
||||||
|
#define PB6_RPORT PINB
|
||||||
|
#define PB6_WPORT PORTB
|
||||||
|
#define PB6_DDR DDRB
|
||||||
|
#define PB6_PWM NULL
|
||||||
|
#undef PB7
|
||||||
|
#define PB7_PIN PINB7
|
||||||
|
#define PB7_RPORT PINB
|
||||||
|
#define PB7_WPORT PORTB
|
||||||
|
#define PB7_DDR DDRB
|
||||||
|
#define PB7_PWM &OCR0A
|
||||||
|
|
||||||
|
#undef PC0
|
||||||
|
#define PC0_PIN PINC0
|
||||||
|
#define PC0_RPORT PINC
|
||||||
|
#define PC0_WPORT PORTC
|
||||||
|
#define PC0_DDR DDRC
|
||||||
|
#define PC0_PWM NULL
|
||||||
|
#undef PC1
|
||||||
|
#define PC1_PIN PINC1
|
||||||
|
#define PC1_RPORT PINC
|
||||||
|
#define PC1_WPORT PORTC
|
||||||
|
#define PC1_DDR DDRC
|
||||||
|
#define PC1_PWM NULL
|
||||||
|
#undef PC2
|
||||||
|
#define PC2_PIN PINC2
|
||||||
|
#define PC2_RPORT PINC
|
||||||
|
#define PC2_WPORT PORTC
|
||||||
|
#define PC2_DDR DDRC
|
||||||
|
#define PC2_PWM NULL
|
||||||
|
#undef PC3
|
||||||
|
#define PC3_PIN PINC3
|
||||||
|
#define PC3_RPORT PINC
|
||||||
|
#define PC3_WPORT PORTC
|
||||||
|
#define PC3_DDR DDRC
|
||||||
|
#define PC3_PWM NULL
|
||||||
|
#undef PC4
|
||||||
|
#define PC4_PIN PINC4
|
||||||
|
#define PC4_RPORT PINC
|
||||||
|
#define PC4_WPORT PORTC
|
||||||
|
#define PC4_DDR DDRC
|
||||||
|
#define PC4_PWM NULL
|
||||||
|
#undef PC5
|
||||||
|
#define PC5_PIN PINC5
|
||||||
|
#define PC5_RPORT PINC
|
||||||
|
#define PC5_WPORT PORTC
|
||||||
|
#define PC5_DDR DDRC
|
||||||
|
#define PC5_PWM NULL
|
||||||
|
#undef PC6
|
||||||
|
#define PC6_PIN PINC6
|
||||||
|
#define PC6_RPORT PINC
|
||||||
|
#define PC6_WPORT PORTC
|
||||||
|
#define PC6_DDR DDRC
|
||||||
|
#define PC6_PWM NULL
|
||||||
|
#undef PC7
|
||||||
|
#define PC7_PIN PINC7
|
||||||
|
#define PC7_RPORT PINC
|
||||||
|
#define PC7_WPORT PORTC
|
||||||
|
#define PC7_DDR DDRC
|
||||||
|
#define PC7_PWM NULL
|
||||||
|
|
||||||
|
#undef PD0
|
||||||
|
#define PD0_PIN PIND0
|
||||||
|
#define PD0_RPORT PIND
|
||||||
|
#define PD0_WPORT PORTD
|
||||||
|
#define PD0_DDR DDRD
|
||||||
|
#define PD0_PWM NULL
|
||||||
|
#undef PD1
|
||||||
|
#define PD1_PIN PIND1
|
||||||
|
#define PD1_RPORT PIND
|
||||||
|
#define PD1_WPORT PORTD
|
||||||
|
#define PD1_DDR DDRD
|
||||||
|
#define PD1_PWM NULL
|
||||||
|
#undef PD2
|
||||||
|
#define PD2_PIN PIND2
|
||||||
|
#define PD2_RPORT PIND
|
||||||
|
#define PD2_WPORT PORTD
|
||||||
|
#define PD2_DDR DDRD
|
||||||
|
#define PD2_PWM NULL
|
||||||
|
#undef PD3
|
||||||
|
#define PD3_PIN PIND3
|
||||||
|
#define PD3_RPORT PIND
|
||||||
|
#define PD3_WPORT PORTD
|
||||||
|
#define PD3_DDR DDRD
|
||||||
|
#define PD3_PWM NULL
|
||||||
|
#undef PD4
|
||||||
|
#define PD4_PIN PIND4
|
||||||
|
#define PD4_RPORT PIND
|
||||||
|
#define PD4_WPORT PORTD
|
||||||
|
#define PD4_DDR DDRD
|
||||||
|
#define PD4_PWM NULL
|
||||||
|
#undef PD5
|
||||||
|
#define PD5_PIN PIND5
|
||||||
|
#define PD5_RPORT PIND
|
||||||
|
#define PD5_WPORT PORTD
|
||||||
|
#define PD5_DDR DDRD
|
||||||
|
#define PD5_PWM NULL
|
||||||
|
#undef PD6
|
||||||
|
#define PD6_PIN PIND6
|
||||||
|
#define PD6_RPORT PIND
|
||||||
|
#define PD6_WPORT PORTD
|
||||||
|
#define PD6_DDR DDRD
|
||||||
|
#define PD6_PWM NULL
|
||||||
|
#undef PD7
|
||||||
|
#define PD7_PIN PIND7
|
||||||
|
#define PD7_RPORT PIND
|
||||||
|
#define PD7_WPORT PORTD
|
||||||
|
#define PD7_DDR DDRD
|
||||||
|
#define PD7_PWM NULL
|
||||||
|
|
||||||
|
#undef PE0
|
||||||
|
#define PE0_PIN PINE0
|
||||||
|
#define PE0_RPORT PINE
|
||||||
|
#define PE0_WPORT PORTE
|
||||||
|
#define PE0_DDR DDRE
|
||||||
|
#define PE0_PWM NULL
|
||||||
|
#undef PE1
|
||||||
|
#define PE1_PIN PINE1
|
||||||
|
#define PE1_RPORT PINE
|
||||||
|
#define PE1_WPORT PORTE
|
||||||
|
#define PE1_DDR DDRE
|
||||||
|
#define PE1_PWM NULL
|
||||||
|
#undef PE2
|
||||||
|
#define PE2_PIN PINE2
|
||||||
|
#define PE2_RPORT PINE
|
||||||
|
#define PE2_WPORT PORTE
|
||||||
|
#define PE2_DDR DDRE
|
||||||
|
#define PE2_PWM NULL
|
||||||
|
#undef PE3
|
||||||
|
#define PE3_PIN PINE3
|
||||||
|
#define PE3_RPORT PINE
|
||||||
|
#define PE3_WPORT PORTE
|
||||||
|
#define PE3_DDR DDRE
|
||||||
|
#define PE3_PWM &OCR3AL
|
||||||
|
#undef PE4
|
||||||
|
#define PE4_PIN PINE4
|
||||||
|
#define PE4_RPORT PINE
|
||||||
|
#define PE4_WPORT PORTE
|
||||||
|
#define PE4_DDR DDRE
|
||||||
|
#define PE4_PWM &OCR3BL
|
||||||
|
#undef PE5
|
||||||
|
#define PE5_PIN PINE5
|
||||||
|
#define PE5_RPORT PINE
|
||||||
|
#define PE5_WPORT PORTE
|
||||||
|
#define PE5_DDR DDRE
|
||||||
|
#define PE5_PWM &OCR3CL
|
||||||
|
#undef PE6
|
||||||
|
#define PE6_PIN PINE6
|
||||||
|
#define PE6_RPORT PINE
|
||||||
|
#define PE6_WPORT PORTE
|
||||||
|
#define PE6_DDR DDRE
|
||||||
|
#define PE6_PWM NULL
|
||||||
|
#undef PE7
|
||||||
|
#define PE7_PIN PINE7
|
||||||
|
#define PE7_RPORT PINE
|
||||||
|
#define PE7_WPORT PORTE
|
||||||
|
#define PE7_DDR DDRE
|
||||||
|
#define PE7_PWM NULL
|
||||||
|
|
||||||
|
#undef PF0
|
||||||
|
#define PF0_PIN PINF0
|
||||||
|
#define PF0_RPORT PINF
|
||||||
|
#define PF0_WPORT PORTF
|
||||||
|
#define PF0_DDR DDRF
|
||||||
|
#define PF0_PWM NULL
|
||||||
|
#undef PF1
|
||||||
|
#define PF1_PIN PINF1
|
||||||
|
#define PF1_RPORT PINF
|
||||||
|
#define PF1_WPORT PORTF
|
||||||
|
#define PF1_DDR DDRF
|
||||||
|
#define PF1_PWM NULL
|
||||||
|
#undef PF2
|
||||||
|
#define PF2_PIN PINF2
|
||||||
|
#define PF2_RPORT PINF
|
||||||
|
#define PF2_WPORT PORTF
|
||||||
|
#define PF2_DDR DDRF
|
||||||
|
#define PF2_PWM NULL
|
||||||
|
#undef PF3
|
||||||
|
#define PF3_PIN PINF3
|
||||||
|
#define PF3_RPORT PINF
|
||||||
|
#define PF3_WPORT PORTF
|
||||||
|
#define PF3_DDR DDRF
|
||||||
|
#define PF3_PWM NULL
|
||||||
|
#undef PF4
|
||||||
|
#define PF4_PIN PINF4
|
||||||
|
#define PF4_RPORT PINF
|
||||||
|
#define PF4_WPORT PORTF
|
||||||
|
#define PF4_DDR DDRF
|
||||||
|
#define PF4_PWM NULL
|
||||||
|
#undef PF5
|
||||||
|
#define PF5_PIN PINF5
|
||||||
|
#define PF5_RPORT PINF
|
||||||
|
#define PF5_WPORT PORTF
|
||||||
|
#define PF5_DDR DDRF
|
||||||
|
#define PF5_PWM NULL
|
||||||
|
#undef PF6
|
||||||
|
#define PF6_PIN PINF6
|
||||||
|
#define PF6_RPORT PINF
|
||||||
|
#define PF6_WPORT PORTF
|
||||||
|
#define PF6_DDR DDRF
|
||||||
|
#define PF6_PWM NULL
|
||||||
|
#undef PF7
|
||||||
|
#define PF7_PIN PINF7
|
||||||
|
#define PF7_RPORT PINF
|
||||||
|
#define PF7_WPORT PORTF
|
||||||
|
#define PF7_DDR DDRF
|
||||||
|
#define PF7_PWM NULL
|
||||||
|
|
||||||
|
#undef PG0
|
||||||
|
#define PG0_PIN PING0
|
||||||
|
#define PG0_RPORT PING
|
||||||
|
#define PG0_WPORT PORTG
|
||||||
|
#define PG0_DDR DDRG
|
||||||
|
#define PG0_PWM NULL
|
||||||
|
#undef PG1
|
||||||
|
#define PG1_PIN PING1
|
||||||
|
#define PG1_RPORT PING
|
||||||
|
#define PG1_WPORT PORTG
|
||||||
|
#define PG1_DDR DDRG
|
||||||
|
#define PG1_PWM NULL
|
||||||
|
#undef PG2
|
||||||
|
#define PG2_PIN PING2
|
||||||
|
#define PG2_RPORT PING
|
||||||
|
#define PG2_WPORT PORTG
|
||||||
|
#define PG2_DDR DDRG
|
||||||
|
#define PG2_PWM NULL
|
||||||
|
#undef PG3
|
||||||
|
#define PG3_PIN PING3
|
||||||
|
#define PG3_RPORT PING
|
||||||
|
#define PG3_WPORT PORTG
|
||||||
|
#define PG3_DDR DDRG
|
||||||
|
#define PG3_PWM NULL
|
||||||
|
#undef PG4
|
||||||
|
#define PG4_PIN PING4
|
||||||
|
#define PG4_RPORT PING
|
||||||
|
#define PG4_WPORT PORTG
|
||||||
|
#define PG4_DDR DDRG
|
||||||
|
#define PG4_PWM NULL
|
||||||
|
#undef PG5
|
||||||
|
#define PG5_PIN PING5
|
||||||
|
#define PG5_RPORT PING
|
||||||
|
#define PG5_WPORT PORTG
|
||||||
|
#define PG5_DDR DDRG
|
||||||
|
#define PG5_PWM &OCR0B
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef DIO0_PIN
|
#ifndef DIO0_PIN
|
||||||
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request
|
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif /* _FASTIO_ARDUINO_H */
|
#endif /* _FASTIO_ARDUINO_H */
|
||||||
|
|
864
Marlin/pins.h
864
Marlin/pins.h
File diff suppressed because it is too large
Load diff
|
@ -98,7 +98,7 @@ volatile unsigned char block_buffer_tail; // Index of the block to pro
|
||||||
//=============================private variables ============================
|
//=============================private variables ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
bool allow_cold_extrude=false;
|
float extrude_min_temp=EXTRUDE_MINTEMP;
|
||||||
#endif
|
#endif
|
||||||
#ifdef XY_FREQUENCY_LIMIT
|
#ifdef XY_FREQUENCY_LIMIT
|
||||||
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
|
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
|
||||||
|
@ -439,12 +439,20 @@ void check_axes_activity()
|
||||||
unsigned char z_active = 0;
|
unsigned char z_active = 0;
|
||||||
unsigned char e_active = 0;
|
unsigned char e_active = 0;
|
||||||
unsigned char tail_fan_speed = fanSpeed;
|
unsigned char tail_fan_speed = fanSpeed;
|
||||||
|
#ifdef BARICUDA
|
||||||
|
unsigned char tail_valve_pressure = ValvePressure;
|
||||||
|
unsigned char tail_e_to_p_pressure = EtoPPressure;
|
||||||
|
#endif
|
||||||
block_t *block;
|
block_t *block;
|
||||||
|
|
||||||
if(block_buffer_tail != block_buffer_head)
|
if(block_buffer_tail != block_buffer_head)
|
||||||
{
|
{
|
||||||
uint8_t block_index = block_buffer_tail;
|
uint8_t block_index = block_buffer_tail;
|
||||||
tail_fan_speed = block_buffer[block_index].fan_speed;
|
tail_fan_speed = block_buffer[block_index].fan_speed;
|
||||||
|
#ifdef BARICUDA
|
||||||
|
tail_valve_pressure = block_buffer[block_index].valve_pressure;
|
||||||
|
tail_e_to_p_pressure = block_buffer[block_index].e_to_p_pressure;
|
||||||
|
#endif
|
||||||
while(block_index != block_buffer_head)
|
while(block_index != block_buffer_head)
|
||||||
{
|
{
|
||||||
block = &block_buffer[block_index];
|
block = &block_buffer[block_index];
|
||||||
|
@ -464,7 +472,7 @@ void check_axes_activity()
|
||||||
disable_e1();
|
disable_e1();
|
||||||
disable_e2();
|
disable_e2();
|
||||||
}
|
}
|
||||||
#if FAN_PIN > -1
|
#if defined(FAN_PIN) && FAN_PIN > -1
|
||||||
#ifndef FAN_SOFT_PWM
|
#ifndef FAN_SOFT_PWM
|
||||||
#ifdef FAN_KICKSTART_TIME
|
#ifdef FAN_KICKSTART_TIME
|
||||||
static unsigned long fan_kick_end;
|
static unsigned long fan_kick_end;
|
||||||
|
@ -486,6 +494,16 @@ void check_axes_activity()
|
||||||
#ifdef AUTOTEMP
|
#ifdef AUTOTEMP
|
||||||
getHighESpeed();
|
getHighESpeed();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef BARICUDA
|
||||||
|
#if defined(HEATER_1_PIN) && HEATER_1_PIN > -1
|
||||||
|
analogWrite(HEATER_1_PIN,tail_valve_pressure);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(HEATER_2_PIN) && HEATER_2_PIN > -1
|
||||||
|
analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -519,7 +537,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
if(target[E_AXIS]!=position[E_AXIS])
|
if(target[E_AXIS]!=position[E_AXIS])
|
||||||
{
|
{
|
||||||
if(degHotend(active_extruder)<EXTRUDE_MINTEMP && !allow_cold_extrude)
|
if(degHotend(active_extruder)<extrude_min_temp)
|
||||||
{
|
{
|
||||||
position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part
|
position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part
|
||||||
SERIAL_ECHO_START;
|
SERIAL_ECHO_START;
|
||||||
|
@ -559,6 +577,10 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
}
|
}
|
||||||
|
|
||||||
block->fan_speed = fanSpeed;
|
block->fan_speed = fanSpeed;
|
||||||
|
#ifdef BARICUDA
|
||||||
|
block->valve_pressure = ValvePressure;
|
||||||
|
block->e_to_p_pressure = EtoPPressure;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Compute direction bits for this block
|
// Compute direction bits for this block
|
||||||
block->direction_bits = 0;
|
block->direction_bits = 0;
|
||||||
|
@ -896,12 +918,12 @@ uint8_t movesplanned()
|
||||||
return (block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
|
return (block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void allow_cold_extrudes(bool allow)
|
|
||||||
{
|
|
||||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
allow_cold_extrude=allow;
|
void set_extrude_min_temp(float temp)
|
||||||
#endif
|
{
|
||||||
|
extrude_min_temp=temp;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Calculate the steps/s^2 acceleration rates, based on the mm/s^s
|
// Calculate the steps/s^2 acceleration rates, based on the mm/s^s
|
||||||
void reset_acceleration_rates()
|
void reset_acceleration_rates()
|
||||||
|
|
|
@ -60,6 +60,10 @@ 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
|
||||||
|
unsigned long valve_pressure;
|
||||||
|
unsigned long e_to_p_pressure;
|
||||||
|
#endif
|
||||||
volatile char busy;
|
volatile char busy;
|
||||||
} block_t;
|
} block_t;
|
||||||
|
|
||||||
|
@ -135,7 +139,9 @@ FORCE_INLINE bool blocks_queued()
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void allow_cold_extrudes(bool allow);
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
|
void set_extrude_min_temp(float temp);
|
||||||
|
#endif
|
||||||
|
|
||||||
void reset_acceleration_rates();
|
void reset_acceleration_rates();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
#include "language.h"
|
#include "language.h"
|
||||||
#include "cardreader.h"
|
#include "cardreader.h"
|
||||||
#include "speed_lookuptable.h"
|
#include "speed_lookuptable.h"
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -69,9 +69,9 @@ volatile long endstops_stepsTotal,endstops_stepsDone;
|
||||||
static volatile bool endstop_x_hit=false;
|
static volatile bool endstop_x_hit=false;
|
||||||
static volatile bool endstop_y_hit=false;
|
static volatile bool endstop_y_hit=false;
|
||||||
static volatile bool endstop_z_hit=false;
|
static volatile bool endstop_z_hit=false;
|
||||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
bool abort_on_endstop_hit = false;
|
bool abort_on_endstop_hit = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static bool old_x_min_endstop=false;
|
static bool old_x_min_endstop=false;
|
||||||
static bool old_x_max_endstop=false;
|
static bool old_x_max_endstop=false;
|
||||||
|
@ -184,20 +184,20 @@ void checkHitEndstops()
|
||||||
SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]);
|
SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]);
|
||||||
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Z");
|
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Z");
|
||||||
}
|
}
|
||||||
SERIAL_ECHOLN("");
|
SERIAL_ECHOLN("");
|
||||||
endstop_x_hit=false;
|
endstop_x_hit=false;
|
||||||
endstop_y_hit=false;
|
endstop_y_hit=false;
|
||||||
endstop_z_hit=false;
|
endstop_z_hit=false;
|
||||||
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
if (abort_on_endstop_hit)
|
if (abort_on_endstop_hit)
|
||||||
{
|
{
|
||||||
card.sdprinting = false;
|
card.sdprinting = false;
|
||||||
card.closefile();
|
card.closefile();
|
||||||
quickStop();
|
quickStop();
|
||||||
setTargetHotend0(0);
|
setTargetHotend0(0);
|
||||||
setTargetHotend1(0);
|
setTargetHotend1(0);
|
||||||
setTargetHotend2(0);
|
setTargetHotend2(0);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -353,7 +353,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_direction[X_AXIS]=-1;
|
count_direction[X_AXIS]=-1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if X_MIN_PIN > -1
|
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
||||||
bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
|
bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
|
||||||
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
||||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||||
|
@ -372,7 +372,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_direction[X_AXIS]=1;
|
count_direction[X_AXIS]=1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if X_MAX_PIN > -1
|
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
||||||
bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
|
bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
|
||||||
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
||||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||||
|
@ -391,7 +391,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_direction[Y_AXIS]=-1;
|
count_direction[Y_AXIS]=-1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if Y_MIN_PIN > -1
|
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
||||||
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOPS_INVERTING);
|
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOPS_INVERTING);
|
||||||
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
|
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
|
||||||
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
||||||
|
@ -409,7 +409,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_direction[Y_AXIS]=1;
|
count_direction[Y_AXIS]=1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if Y_MAX_PIN > -1
|
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
||||||
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOPS_INVERTING);
|
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOPS_INVERTING);
|
||||||
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
|
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
|
||||||
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
|
||||||
|
@ -452,7 +452,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_direction[Z_AXIS]=-1;
|
count_direction[Z_AXIS]=-1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if Z_MIN_PIN > -1
|
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
||||||
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOPS_INVERTING);
|
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOPS_INVERTING);
|
||||||
if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
|
if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
|
||||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||||
|
@ -473,7 +473,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_direction[Z_AXIS]=1;
|
count_direction[Z_AXIS]=1;
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if Z_MAX_PIN > -1
|
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
|
||||||
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOPS_INVERTING);
|
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOPS_INVERTING);
|
||||||
if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
|
if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
|
||||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||||
|
@ -743,20 +743,20 @@ void st_init()
|
||||||
microstep_init(); //Initialize Microstepping Pins
|
microstep_init(); //Initialize Microstepping Pins
|
||||||
|
|
||||||
//Initialize Dir Pins
|
//Initialize Dir Pins
|
||||||
#if X_DIR_PIN > -1
|
#if defined(X_DIR_PIN) && X_DIR_PIN > -1
|
||||||
SET_OUTPUT(X_DIR_PIN);
|
SET_OUTPUT(X_DIR_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if Y_DIR_PIN > -1
|
#if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
|
||||||
SET_OUTPUT(Y_DIR_PIN);
|
SET_OUTPUT(Y_DIR_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if Z_DIR_PIN > -1
|
#if defined(Z_DIR_PIN) && Z_DIR_PIN > -1
|
||||||
SET_OUTPUT(Z_DIR_PIN);
|
SET_OUTPUT(Z_DIR_PIN);
|
||||||
|
|
||||||
#if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_DIR_PIN > -1)
|
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && (Z2_DIR_PIN > -1)
|
||||||
SET_OUTPUT(Z2_DIR_PIN);
|
SET_OUTPUT(Z2_DIR_PIN);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if E0_DIR_PIN > -1
|
#if defined(E0_DIR_PIN) && E0_DIR_PIN > -1
|
||||||
SET_OUTPUT(E0_DIR_PIN);
|
SET_OUTPUT(E0_DIR_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
|
#if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
|
||||||
|
@ -768,24 +768,24 @@ void st_init()
|
||||||
|
|
||||||
//Initialize Enable Pins - steppers default to disabled.
|
//Initialize Enable Pins - steppers default to disabled.
|
||||||
|
|
||||||
#if (X_ENABLE_PIN > -1)
|
#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
|
||||||
SET_OUTPUT(X_ENABLE_PIN);
|
SET_OUTPUT(X_ENABLE_PIN);
|
||||||
if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
|
if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#if (Y_ENABLE_PIN > -1)
|
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
|
||||||
SET_OUTPUT(Y_ENABLE_PIN);
|
SET_OUTPUT(Y_ENABLE_PIN);
|
||||||
if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
|
if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#if (Z_ENABLE_PIN > -1)
|
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
|
||||||
SET_OUTPUT(Z_ENABLE_PIN);
|
SET_OUTPUT(Z_ENABLE_PIN);
|
||||||
if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
|
if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
|
||||||
|
|
||||||
#if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_ENABLE_PIN > -1)
|
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && (Z2_ENABLE_PIN > -1)
|
||||||
SET_OUTPUT(Z2_ENABLE_PIN);
|
SET_OUTPUT(Z2_ENABLE_PIN);
|
||||||
if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
|
if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if (E0_ENABLE_PIN > -1)
|
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
|
||||||
SET_OUTPUT(E0_ENABLE_PIN);
|
SET_OUTPUT(E0_ENABLE_PIN);
|
||||||
if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
|
if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
|
@ -800,42 +800,42 @@ void st_init()
|
||||||
|
|
||||||
//endstops and pullups
|
//endstops and pullups
|
||||||
|
|
||||||
#if X_MIN_PIN > -1
|
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
||||||
SET_INPUT(X_MIN_PIN);
|
SET_INPUT(X_MIN_PIN);
|
||||||
#ifdef ENDSTOPPULLUP_XMIN
|
#ifdef ENDSTOPPULLUP_XMIN
|
||||||
WRITE(X_MIN_PIN,HIGH);
|
WRITE(X_MIN_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Y_MIN_PIN > -1
|
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
||||||
SET_INPUT(Y_MIN_PIN);
|
SET_INPUT(Y_MIN_PIN);
|
||||||
#ifdef ENDSTOPPULLUP_YMIN
|
#ifdef ENDSTOPPULLUP_YMIN
|
||||||
WRITE(Y_MIN_PIN,HIGH);
|
WRITE(Y_MIN_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Z_MIN_PIN > -1
|
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
||||||
SET_INPUT(Z_MIN_PIN);
|
SET_INPUT(Z_MIN_PIN);
|
||||||
#ifdef ENDSTOPPULLUP_ZMIN
|
#ifdef ENDSTOPPULLUP_ZMIN
|
||||||
WRITE(Z_MIN_PIN,HIGH);
|
WRITE(Z_MIN_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if X_MAX_PIN > -1
|
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
||||||
SET_INPUT(X_MAX_PIN);
|
SET_INPUT(X_MAX_PIN);
|
||||||
#ifdef ENDSTOPPULLUP_XMAX
|
#ifdef ENDSTOPPULLUP_XMAX
|
||||||
WRITE(X_MAX_PIN,HIGH);
|
WRITE(X_MAX_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Y_MAX_PIN > -1
|
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
||||||
SET_INPUT(Y_MAX_PIN);
|
SET_INPUT(Y_MAX_PIN);
|
||||||
#ifdef ENDSTOPPULLUP_YMAX
|
#ifdef ENDSTOPPULLUP_YMAX
|
||||||
WRITE(Y_MAX_PIN,HIGH);
|
WRITE(Y_MAX_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Z_MAX_PIN > -1
|
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
|
||||||
SET_INPUT(Z_MAX_PIN);
|
SET_INPUT(Z_MAX_PIN);
|
||||||
#ifdef ENDSTOPPULLUP_ZMAX
|
#ifdef ENDSTOPPULLUP_ZMAX
|
||||||
WRITE(Z_MAX_PIN,HIGH);
|
WRITE(Z_MAX_PIN,HIGH);
|
||||||
|
@ -844,26 +844,26 @@ void st_init()
|
||||||
|
|
||||||
|
|
||||||
//Initialize Step Pins
|
//Initialize Step Pins
|
||||||
#if (X_STEP_PIN > -1)
|
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
|
||||||
SET_OUTPUT(X_STEP_PIN);
|
SET_OUTPUT(X_STEP_PIN);
|
||||||
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
||||||
disable_x();
|
disable_x();
|
||||||
#endif
|
#endif
|
||||||
#if (Y_STEP_PIN > -1)
|
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Y_STEP_PIN);
|
SET_OUTPUT(Y_STEP_PIN);
|
||||||
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
||||||
disable_y();
|
disable_y();
|
||||||
#endif
|
#endif
|
||||||
#if (Z_STEP_PIN > -1)
|
#if defined(Z_STEP_PIN) && (Z_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Z_STEP_PIN);
|
SET_OUTPUT(Z_STEP_PIN);
|
||||||
WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
|
WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
|
||||||
#if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_STEP_PIN > -1)
|
#if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && (Z2_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Z2_STEP_PIN);
|
SET_OUTPUT(Z2_STEP_PIN);
|
||||||
WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
|
WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
|
||||||
#endif
|
#endif
|
||||||
disable_z();
|
disable_z();
|
||||||
#endif
|
#endif
|
||||||
#if (E0_STEP_PIN > -1)
|
#if defined(E0_STEP_PIN) && (E0_STEP_PIN > -1)
|
||||||
SET_OUTPUT(E0_STEP_PIN);
|
SET_OUTPUT(E0_STEP_PIN);
|
||||||
WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
|
WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
|
||||||
disable_e0();
|
disable_e0();
|
||||||
|
@ -879,10 +879,6 @@ void st_init()
|
||||||
disable_e2();
|
disable_e2();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CONTROLLERFAN_PIN
|
|
||||||
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// waveform generation = 0100 = CTC
|
// waveform generation = 0100 = CTC
|
||||||
TCCR1B &= ~(1<<WGM13);
|
TCCR1B &= ~(1<<WGM13);
|
||||||
TCCR1B |= (1<<WGM12);
|
TCCR1B |= (1<<WGM12);
|
||||||
|
@ -978,7 +974,7 @@ void quickStop()
|
||||||
|
|
||||||
void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example
|
void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example
|
||||||
{
|
{
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||||
digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
|
digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
|
||||||
SPI.transfer(address); // send in the address and value via SPI:
|
SPI.transfer(address); // send in the address and value via SPI:
|
||||||
SPI.transfer(value);
|
SPI.transfer(value);
|
||||||
|
@ -989,7 +985,7 @@ void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl e
|
||||||
|
|
||||||
void digipot_init() //Initialize Digipot Motor Current
|
void digipot_init() //Initialize Digipot Motor Current
|
||||||
{
|
{
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||||
const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
|
const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
|
||||||
|
|
||||||
SPI.begin();
|
SPI.begin();
|
||||||
|
@ -1002,7 +998,7 @@ void digipot_init() //Initialize Digipot Motor Current
|
||||||
|
|
||||||
void digipot_current(uint8_t driver, int current)
|
void digipot_current(uint8_t driver, int current)
|
||||||
{
|
{
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
|
||||||
const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
|
const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
|
||||||
digitalPotWrite(digipot_ch[driver], current);
|
digitalPotWrite(digipot_ch[driver], current);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1010,7 +1006,7 @@ void digipot_current(uint8_t driver, int current)
|
||||||
|
|
||||||
void microstep_init()
|
void microstep_init()
|
||||||
{
|
{
|
||||||
#if X_MS1_PIN > -1
|
#if defined(X_MS1_PIN) && X_MS1_PIN > -1
|
||||||
const uint8_t microstep_modes[] = MICROSTEP_MODES;
|
const uint8_t microstep_modes[] = MICROSTEP_MODES;
|
||||||
pinMode(X_MS2_PIN,OUTPUT);
|
pinMode(X_MS2_PIN,OUTPUT);
|
||||||
pinMode(Y_MS2_PIN,OUTPUT);
|
pinMode(Y_MS2_PIN,OUTPUT);
|
||||||
|
|
|
@ -40,10 +40,13 @@
|
||||||
int target_temperature[EXTRUDERS] = { 0 };
|
int target_temperature[EXTRUDERS] = { 0 };
|
||||||
int target_temperature_bed = 0;
|
int target_temperature_bed = 0;
|
||||||
int current_temperature_raw[EXTRUDERS] = { 0 };
|
int current_temperature_raw[EXTRUDERS] = { 0 };
|
||||||
float current_temperature[EXTRUDERS] = { 0 };
|
float current_temperature[EXTRUDERS] = { 0.0 };
|
||||||
int current_temperature_bed_raw = 0;
|
int current_temperature_bed_raw = 0;
|
||||||
float current_temperature_bed = 0;
|
float current_temperature_bed = 0.0;
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
int redundant_temperature_raw = 0;
|
||||||
|
float redundant_temperature = 0.0;
|
||||||
|
#endif
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
float Kp=DEFAULT_Kp;
|
float Kp=DEFAULT_Kp;
|
||||||
float Ki=(DEFAULT_Ki*PID_dT);
|
float Ki=(DEFAULT_Ki*PID_dT);
|
||||||
|
@ -99,17 +102,20 @@ static volatile bool temp_meas_ready = false;
|
||||||
#ifdef FAN_SOFT_PWM
|
#ifdef FAN_SOFT_PWM
|
||||||
static unsigned char soft_pwm_fan;
|
static unsigned char soft_pwm_fan;
|
||||||
#endif
|
#endif
|
||||||
|
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
|
||||||
|
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
|
||||||
|
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
|
||||||
|
static unsigned long extruder_autofan_last_check;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#if EXTRUDERS > 3
|
#if EXTRUDERS > 3
|
||||||
# error Unsupported number of extruders
|
# error Unsupported number of extruders
|
||||||
#elif EXTRUDERS > 2
|
#elif EXTRUDERS > 2
|
||||||
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
|
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
|
||||||
#elif EXTRUDERS > 1
|
#elif EXTRUDERS > 1
|
||||||
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
|
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
|
||||||
#else
|
#else
|
||||||
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
|
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Init min and max temp with extreme values to prevent false errors during startup
|
// Init min and max temp with extreme values to prevent false errors during startup
|
||||||
|
@ -121,8 +127,14 @@ static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383 );
|
||||||
#ifdef BED_MAXTEMP
|
#ifdef BED_MAXTEMP
|
||||||
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
||||||
#endif
|
#endif
|
||||||
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
|
||||||
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE };
|
||||||
|
static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN };
|
||||||
|
#else
|
||||||
|
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
||||||
|
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
||||||
|
#endif
|
||||||
|
|
||||||
static float analog2temp(int raw, uint8_t e);
|
static float analog2temp(int raw, uint8_t e);
|
||||||
static float analog2tempBed(int raw);
|
static float analog2tempBed(int raw);
|
||||||
|
@ -154,28 +166,28 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
float Kp, Ki, Kd;
|
float Kp, Ki, Kd;
|
||||||
float max = 0, min = 10000;
|
float max = 0, min = 10000;
|
||||||
|
|
||||||
if ((extruder > EXTRUDERS)
|
if ((extruder > EXTRUDERS)
|
||||||
#if (TEMP_BED_PIN <= -1)
|
#if (TEMP_BED_PIN <= -1)
|
||||||
||(extruder < 0)
|
||(extruder < 0)
|
||||||
#endif
|
#endif
|
||||||
){
|
){
|
||||||
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
|
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_ECHOLN("PID Autotune start");
|
SERIAL_ECHOLN("PID Autotune start");
|
||||||
|
|
||||||
disable_heater(); // switch off all heaters.
|
disable_heater(); // switch off all heaters.
|
||||||
|
|
||||||
if (extruder<0)
|
if (extruder<0)
|
||||||
{
|
{
|
||||||
soft_pwm_bed = (MAX_BED_POWER)/2;
|
soft_pwm_bed = (MAX_BED_POWER)/2;
|
||||||
bias = d = (MAX_BED_POWER)/2;
|
bias = d = (MAX_BED_POWER)/2;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
soft_pwm[extruder] = (PID_MAX)/2;
|
soft_pwm[extruder] = (PID_MAX)/2;
|
||||||
bias = d = (PID_MAX)/2;
|
bias = d = (PID_MAX)/2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -193,10 +205,10 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
if(heating == true && input > temp) {
|
if(heating == true && input > temp) {
|
||||||
if(millis() - t2 > 5000) {
|
if(millis() - t2 > 5000) {
|
||||||
heating=false;
|
heating=false;
|
||||||
if (extruder<0)
|
if (extruder<0)
|
||||||
soft_pwm_bed = (bias - d) >> 1;
|
soft_pwm_bed = (bias - d) >> 1;
|
||||||
else
|
else
|
||||||
soft_pwm[extruder] = (bias - d) >> 1;
|
soft_pwm[extruder] = (bias - d) >> 1;
|
||||||
t1=millis();
|
t1=millis();
|
||||||
t_high=t1 - t2;
|
t_high=t1 - t2;
|
||||||
max=temp;
|
max=temp;
|
||||||
|
@ -247,10 +259,10 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
*/
|
*/
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (extruder<0)
|
if (extruder<0)
|
||||||
soft_pwm_bed = (bias + d) >> 1;
|
soft_pwm_bed = (bias + d) >> 1;
|
||||||
else
|
else
|
||||||
soft_pwm[extruder] = (bias + d) >> 1;
|
soft_pwm[extruder] = (bias + d) >> 1;
|
||||||
cycles++;
|
cycles++;
|
||||||
min=temp;
|
min=temp;
|
||||||
}
|
}
|
||||||
|
@ -261,14 +273,14 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if(millis() - temp_millis > 2000) {
|
if(millis() - temp_millis > 2000) {
|
||||||
int p;
|
int p;
|
||||||
if (extruder<0){
|
if (extruder<0){
|
||||||
p=soft_pwm_bed;
|
p=soft_pwm_bed;
|
||||||
SERIAL_PROTOCOLPGM("ok B:");
|
SERIAL_PROTOCOLPGM("ok B:");
|
||||||
}else{
|
}else{
|
||||||
p=soft_pwm[extruder];
|
p=soft_pwm[extruder];
|
||||||
SERIAL_PROTOCOLPGM("ok T:");
|
SERIAL_PROTOCOLPGM("ok T:");
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_PROTOCOL(input);
|
SERIAL_PROTOCOL(input);
|
||||||
SERIAL_PROTOCOLPGM(" @:");
|
SERIAL_PROTOCOLPGM(" @:");
|
||||||
|
@ -306,6 +318,78 @@ int getHeaterPower(int heater) {
|
||||||
return soft_pwm[heater];
|
return soft_pwm[heater];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
|
||||||
|
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
|
||||||
|
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
|
||||||
|
|
||||||
|
#if defined(FAN_PIN) && FAN_PIN > -1
|
||||||
|
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
|
||||||
|
#error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
|
||||||
|
#endif
|
||||||
|
#if EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
|
||||||
|
#error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN"
|
||||||
|
#endif
|
||||||
|
#if EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
|
||||||
|
#error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN"
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void setExtruderAutoFanState(int pin, bool state)
|
||||||
|
{
|
||||||
|
unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0;
|
||||||
|
// this idiom allows both digital and PWM fan outputs (see M42 handling).
|
||||||
|
pinMode(pin, OUTPUT);
|
||||||
|
digitalWrite(pin, newFanSpeed);
|
||||||
|
analogWrite(pin, newFanSpeed);
|
||||||
|
}
|
||||||
|
|
||||||
|
void checkExtruderAutoFans()
|
||||||
|
{
|
||||||
|
uint8_t fanState = 0;
|
||||||
|
|
||||||
|
// which fan pins need to be turned on?
|
||||||
|
#if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
|
||||||
|
if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||||
|
fanState |= 1;
|
||||||
|
#endif
|
||||||
|
#if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
|
||||||
|
if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||||
|
{
|
||||||
|
if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
|
||||||
|
fanState |= 1;
|
||||||
|
else
|
||||||
|
fanState |= 2;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
|
||||||
|
if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE)
|
||||||
|
{
|
||||||
|
if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
|
||||||
|
fanState |= 1;
|
||||||
|
else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
|
||||||
|
fanState |= 2;
|
||||||
|
else
|
||||||
|
fanState |= 4;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// update extruder auto fan states
|
||||||
|
#if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
|
||||||
|
setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
|
||||||
|
#endif
|
||||||
|
#if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
|
||||||
|
if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN)
|
||||||
|
setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
|
||||||
|
#endif
|
||||||
|
#if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
|
||||||
|
if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN
|
||||||
|
&& EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
|
||||||
|
setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // any extruder auto fan pins set
|
||||||
|
|
||||||
void manage_heater()
|
void manage_heater()
|
||||||
{
|
{
|
||||||
float pid_input;
|
float pid_input;
|
||||||
|
@ -396,10 +480,31 @@ void manage_heater()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
if(fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) {
|
||||||
|
disable_heater();
|
||||||
|
if(IsStopped() == false) {
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ERRORLNPGM("Extruder switched off. Temperature difference between temp sensors is too high !");
|
||||||
|
LCD_ALERTMESSAGEPGM("Err: REDUNDANT TEMP ERROR");
|
||||||
|
}
|
||||||
|
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||||
|
Stop();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
} // End extruder for loop
|
} // End extruder for loop
|
||||||
|
|
||||||
|
|
||||||
|
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
|
||||||
|
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
|
||||||
|
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
|
||||||
|
if(millis() - extruder_autofan_last_check > 2500) // only need to check fan state very infrequently
|
||||||
|
{
|
||||||
|
checkExtruderAutoFans();
|
||||||
|
extruder_autofan_last_check = millis();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef PIDTEMPBED
|
#ifndef PIDTEMPBED
|
||||||
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
|
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
|
||||||
return;
|
return;
|
||||||
|
@ -481,7 +586,11 @@ void manage_heater()
|
||||||
// Derived from RepRap FiveD extruder::getTemperature()
|
// Derived from RepRap FiveD extruder::getTemperature()
|
||||||
// For hot end temperature measurement.
|
// For hot end temperature measurement.
|
||||||
static float analog2temp(int raw, uint8_t e) {
|
static float analog2temp(int raw, uint8_t e) {
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
if(e > EXTRUDERS)
|
||||||
|
#else
|
||||||
if(e >= EXTRUDERS)
|
if(e >= EXTRUDERS)
|
||||||
|
#endif
|
||||||
{
|
{
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERROR((int)e);
|
SERIAL_ERROR((int)e);
|
||||||
|
@ -560,7 +669,9 @@ static void updateTemperaturesFromRawValues()
|
||||||
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
||||||
}
|
}
|
||||||
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
|
||||||
|
#endif
|
||||||
//Reset the watchdog after we know we have a temperature measurement.
|
//Reset the watchdog after we know we have a temperature measurement.
|
||||||
watchdog_reset();
|
watchdog_reset();
|
||||||
|
|
||||||
|
@ -571,6 +682,12 @@ static void updateTemperaturesFromRawValues()
|
||||||
|
|
||||||
void tp_init()
|
void tp_init()
|
||||||
{
|
{
|
||||||
|
#if (MOTHERBOARD == 80) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1))
|
||||||
|
//disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
|
||||||
|
MCUCR=(1<<JTD);
|
||||||
|
MCUCR=(1<<JTD);
|
||||||
|
#endif
|
||||||
|
|
||||||
// Finish init of mult extruder arrays
|
// Finish init of mult extruder arrays
|
||||||
for(int e = 0; e < EXTRUDERS; e++) {
|
for(int e = 0; e < EXTRUDERS; e++) {
|
||||||
// populate with the first value
|
// populate with the first value
|
||||||
|
@ -585,19 +702,19 @@ void tp_init()
|
||||||
#endif //PIDTEMPBED
|
#endif //PIDTEMPBED
|
||||||
}
|
}
|
||||||
|
|
||||||
#if (HEATER_0_PIN > -1)
|
#if defined(HEATER_0_PIN) && (HEATER_0_PIN > -1)
|
||||||
SET_OUTPUT(HEATER_0_PIN);
|
SET_OUTPUT(HEATER_0_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if (HEATER_1_PIN > -1)
|
#if defined(HEATER_1_PIN) && (HEATER_1_PIN > -1)
|
||||||
SET_OUTPUT(HEATER_1_PIN);
|
SET_OUTPUT(HEATER_1_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if (HEATER_2_PIN > -1)
|
#if defined(HEATER_2_PIN) && (HEATER_2_PIN > -1)
|
||||||
SET_OUTPUT(HEATER_2_PIN);
|
SET_OUTPUT(HEATER_2_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if (HEATER_BED_PIN > -1)
|
#if defined(HEATER_BED_PIN) && (HEATER_BED_PIN > -1)
|
||||||
SET_OUTPUT(HEATER_BED_PIN);
|
SET_OUTPUT(HEATER_BED_PIN);
|
||||||
#endif
|
#endif
|
||||||
#if (FAN_PIN > -1)
|
#if defined(FAN_PIN) && (FAN_PIN > -1)
|
||||||
SET_OUTPUT(FAN_PIN);
|
SET_OUTPUT(FAN_PIN);
|
||||||
#ifdef FAST_PWM_FAN
|
#ifdef FAST_PWM_FAN
|
||||||
setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
|
setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
|
||||||
|
@ -629,28 +746,28 @@ void tp_init()
|
||||||
#ifdef DIDR2
|
#ifdef DIDR2
|
||||||
DIDR2 = 0;
|
DIDR2 = 0;
|
||||||
#endif
|
#endif
|
||||||
#if (TEMP_0_PIN > -1)
|
#if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
|
||||||
#if TEMP_0_PIN < 8
|
#if TEMP_0_PIN < 8
|
||||||
DIDR0 |= 1 << TEMP_0_PIN;
|
DIDR0 |= 1 << TEMP_0_PIN;
|
||||||
#else
|
#else
|
||||||
DIDR2 |= 1<<(TEMP_0_PIN - 8);
|
DIDR2 |= 1<<(TEMP_0_PIN - 8);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if (TEMP_1_PIN > -1)
|
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
|
||||||
#if TEMP_1_PIN < 8
|
#if TEMP_1_PIN < 8
|
||||||
DIDR0 |= 1<<TEMP_1_PIN;
|
DIDR0 |= 1<<TEMP_1_PIN;
|
||||||
#else
|
#else
|
||||||
DIDR2 |= 1<<(TEMP_1_PIN - 8);
|
DIDR2 |= 1<<(TEMP_1_PIN - 8);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if (TEMP_2_PIN > -1)
|
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
|
||||||
#if TEMP_2_PIN < 8
|
#if TEMP_2_PIN < 8
|
||||||
DIDR0 |= 1 << TEMP_2_PIN;
|
DIDR0 |= 1 << TEMP_2_PIN;
|
||||||
#else
|
#else
|
||||||
DIDR2 = 1<<(TEMP_2_PIN - 8);
|
DIDR2 |= 1<<(TEMP_2_PIN - 8);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if (TEMP_BED_PIN > -1)
|
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
|
||||||
#if TEMP_BED_PIN < 8
|
#if TEMP_BED_PIN < 8
|
||||||
DIDR0 |= 1<<TEMP_BED_PIN;
|
DIDR0 |= 1<<TEMP_BED_PIN;
|
||||||
#else
|
#else
|
||||||
|
@ -689,7 +806,7 @@ void tp_init()
|
||||||
|
|
||||||
#if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
|
#if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
|
||||||
minttemp[1] = HEATER_1_MINTEMP;
|
minttemp[1] = HEATER_1_MINTEMP;
|
||||||
while(analog2temp(minttemp_raw[1], 1) > HEATER_1_MINTEMP) {
|
while(analog2temp(minttemp_raw[1], 1) < HEATER_1_MINTEMP) {
|
||||||
#if HEATER_1_RAW_LO_TEMP < HEATER_1_RAW_HI_TEMP
|
#if HEATER_1_RAW_LO_TEMP < HEATER_1_RAW_HI_TEMP
|
||||||
minttemp_raw[1] += OVERSAMPLENR;
|
minttemp_raw[1] += OVERSAMPLENR;
|
||||||
#else
|
#else
|
||||||
|
@ -710,7 +827,7 @@ void tp_init()
|
||||||
|
|
||||||
#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
|
#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
|
||||||
minttemp[2] = HEATER_2_MINTEMP;
|
minttemp[2] = HEATER_2_MINTEMP;
|
||||||
while(analog2temp(minttemp_raw[2], 2) > HEATER_2_MINTEMP) {
|
while(analog2temp(minttemp_raw[2], 2) < HEATER_2_MINTEMP) {
|
||||||
#if HEATER_2_RAW_LO_TEMP < HEATER_2_RAW_HI_TEMP
|
#if HEATER_2_RAW_LO_TEMP < HEATER_2_RAW_HI_TEMP
|
||||||
minttemp_raw[2] += OVERSAMPLENR;
|
minttemp_raw[2] += OVERSAMPLENR;
|
||||||
#else
|
#else
|
||||||
|
@ -771,34 +888,34 @@ void disable_heater()
|
||||||
for(int i=0;i<EXTRUDERS;i++)
|
for(int i=0;i<EXTRUDERS;i++)
|
||||||
setTargetHotend(0,i);
|
setTargetHotend(0,i);
|
||||||
setTargetBed(0);
|
setTargetBed(0);
|
||||||
#if TEMP_0_PIN > -1
|
#if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
|
||||||
target_temperature[0]=0;
|
target_temperature[0]=0;
|
||||||
soft_pwm[0]=0;
|
soft_pwm[0]=0;
|
||||||
#if HEATER_0_PIN > -1
|
#if defined(HEATER_0_PIN) && HEATER_0_PIN > -1
|
||||||
WRITE(HEATER_0_PIN,LOW);
|
WRITE(HEATER_0_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_1_PIN > -1
|
#if defined(TEMP_1_PIN) && TEMP_1_PIN > -1
|
||||||
target_temperature[1]=0;
|
target_temperature[1]=0;
|
||||||
soft_pwm[1]=0;
|
soft_pwm[1]=0;
|
||||||
#if HEATER_1_PIN > -1
|
#if defined(HEATER_1_PIN) && HEATER_1_PIN > -1
|
||||||
WRITE(HEATER_1_PIN,LOW);
|
WRITE(HEATER_1_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_2_PIN > -1
|
#if defined(TEMP_2_PIN) && TEMP_2_PIN > -1
|
||||||
target_temperature[2]=0;
|
target_temperature[2]=0;
|
||||||
soft_pwm[2]=0;
|
soft_pwm[2]=0;
|
||||||
#if HEATER_2_PIN > -1
|
#if defined(HEATER_2_PIN) && HEATER_2_PIN > -1
|
||||||
WRITE(HEATER_2_PIN,LOW);
|
WRITE(HEATER_2_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_BED_PIN > -1
|
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
|
||||||
target_temperature_bed=0;
|
target_temperature_bed=0;
|
||||||
soft_pwm_bed=0;
|
soft_pwm_bed=0;
|
||||||
#if HEATER_BED_PIN > -1
|
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
|
||||||
WRITE(HEATER_BED_PIN,LOW);
|
WRITE(HEATER_BED_PIN,LOW);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
@ -934,7 +1051,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
soft_pwm_2 = soft_pwm[2];
|
soft_pwm_2 = soft_pwm[2];
|
||||||
if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1);
|
if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1);
|
||||||
#endif
|
#endif
|
||||||
#if HEATER_BED_PIN > -1
|
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
|
||||||
soft_pwm_b = soft_pwm_bed;
|
soft_pwm_b = soft_pwm_bed;
|
||||||
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
|
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
|
||||||
#endif
|
#endif
|
||||||
|
@ -950,7 +1067,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
#if EXTRUDERS > 2
|
#if EXTRUDERS > 2
|
||||||
if(soft_pwm_2 <= pwm_count) WRITE(HEATER_2_PIN,0);
|
if(soft_pwm_2 <= pwm_count) WRITE(HEATER_2_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
#if HEATER_BED_PIN > -1
|
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
|
||||||
if(soft_pwm_b <= pwm_count) WRITE(HEATER_BED_PIN,0);
|
if(soft_pwm_b <= pwm_count) WRITE(HEATER_BED_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
#ifdef FAN_SOFT_PWM
|
#ifdef FAN_SOFT_PWM
|
||||||
|
@ -962,7 +1079,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
|
|
||||||
switch(temp_state) {
|
switch(temp_state) {
|
||||||
case 0: // Prepare TEMP_0
|
case 0: // Prepare TEMP_0
|
||||||
#if (TEMP_0_PIN > -1)
|
#if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
|
||||||
#if TEMP_0_PIN > 7
|
#if TEMP_0_PIN > 7
|
||||||
ADCSRB = 1<<MUX5;
|
ADCSRB = 1<<MUX5;
|
||||||
#else
|
#else
|
||||||
|
@ -975,7 +1092,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
temp_state = 1;
|
temp_state = 1;
|
||||||
break;
|
break;
|
||||||
case 1: // Measure TEMP_0
|
case 1: // Measure TEMP_0
|
||||||
#if (TEMP_0_PIN > -1)
|
#if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
|
||||||
raw_temp_0_value += ADC;
|
raw_temp_0_value += ADC;
|
||||||
#endif
|
#endif
|
||||||
#ifdef HEATER_0_USES_MAX6675 // TODO remove the blocking
|
#ifdef HEATER_0_USES_MAX6675 // TODO remove the blocking
|
||||||
|
@ -984,7 +1101,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
temp_state = 2;
|
temp_state = 2;
|
||||||
break;
|
break;
|
||||||
case 2: // Prepare TEMP_BED
|
case 2: // Prepare TEMP_BED
|
||||||
#if (TEMP_BED_PIN > -1)
|
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
|
||||||
#if TEMP_BED_PIN > 7
|
#if TEMP_BED_PIN > 7
|
||||||
ADCSRB = 1<<MUX5;
|
ADCSRB = 1<<MUX5;
|
||||||
#else
|
#else
|
||||||
|
@ -997,13 +1114,13 @@ ISR(TIMER0_COMPB_vect)
|
||||||
temp_state = 3;
|
temp_state = 3;
|
||||||
break;
|
break;
|
||||||
case 3: // Measure TEMP_BED
|
case 3: // Measure TEMP_BED
|
||||||
#if (TEMP_BED_PIN > -1)
|
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
|
||||||
raw_temp_bed_value += ADC;
|
raw_temp_bed_value += ADC;
|
||||||
#endif
|
#endif
|
||||||
temp_state = 4;
|
temp_state = 4;
|
||||||
break;
|
break;
|
||||||
case 4: // Prepare TEMP_1
|
case 4: // Prepare TEMP_1
|
||||||
#if (TEMP_1_PIN > -1)
|
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
|
||||||
#if TEMP_1_PIN > 7
|
#if TEMP_1_PIN > 7
|
||||||
ADCSRB = 1<<MUX5;
|
ADCSRB = 1<<MUX5;
|
||||||
#else
|
#else
|
||||||
|
@ -1016,13 +1133,13 @@ ISR(TIMER0_COMPB_vect)
|
||||||
temp_state = 5;
|
temp_state = 5;
|
||||||
break;
|
break;
|
||||||
case 5: // Measure TEMP_1
|
case 5: // Measure TEMP_1
|
||||||
#if (TEMP_1_PIN > -1)
|
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
|
||||||
raw_temp_1_value += ADC;
|
raw_temp_1_value += ADC;
|
||||||
#endif
|
#endif
|
||||||
temp_state = 6;
|
temp_state = 6;
|
||||||
break;
|
break;
|
||||||
case 6: // Prepare TEMP_2
|
case 6: // Prepare TEMP_2
|
||||||
#if (TEMP_2_PIN > -1)
|
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
|
||||||
#if TEMP_2_PIN > 7
|
#if TEMP_2_PIN > 7
|
||||||
ADCSRB = 1<<MUX5;
|
ADCSRB = 1<<MUX5;
|
||||||
#else
|
#else
|
||||||
|
@ -1035,7 +1152,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
temp_state = 7;
|
temp_state = 7;
|
||||||
break;
|
break;
|
||||||
case 7: // Measure TEMP_2
|
case 7: // Measure TEMP_2
|
||||||
#if (TEMP_2_PIN > -1)
|
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
|
||||||
raw_temp_2_value += ADC;
|
raw_temp_2_value += ADC;
|
||||||
#endif
|
#endif
|
||||||
temp_state = 0;
|
temp_state = 0;
|
||||||
|
@ -1055,6 +1172,9 @@ ISR(TIMER0_COMPB_vect)
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
current_temperature_raw[1] = raw_temp_1_value;
|
current_temperature_raw[1] = raw_temp_1_value;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
redundant_temperature_raw = raw_temp_1_value;
|
||||||
|
#endif
|
||||||
#if EXTRUDERS > 2
|
#if EXTRUDERS > 2
|
||||||
current_temperature_raw[2] = raw_temp_2_value;
|
current_temperature_raw[2] = raw_temp_2_value;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -37,6 +37,9 @@ extern int target_temperature[EXTRUDERS];
|
||||||
extern float current_temperature[EXTRUDERS];
|
extern float current_temperature[EXTRUDERS];
|
||||||
extern int target_temperature_bed;
|
extern int target_temperature_bed;
|
||||||
extern float current_temperature_bed;
|
extern float current_temperature_bed;
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
extern float redundant_temperature;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
extern float Kp,Ki,Kd,Kc;
|
extern float Kp,Ki,Kd,Kc;
|
||||||
|
|
|
@ -76,7 +76,14 @@ static void menu_action_setting_edit_callback_float51(const char* pstr, float* p
|
||||||
static void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
static void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc);
|
||||||
static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, menuFunc_t callbackFunc);
|
static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, menuFunc_t callbackFunc);
|
||||||
|
|
||||||
#define ENCODER_STEPS_PER_MENU_ITEM 5
|
#define ENCODER_FEEDRATE_DEADZONE 10
|
||||||
|
|
||||||
|
#if !defined(LCD_I2C_VIKI)
|
||||||
|
#define ENCODER_STEPS_PER_MENU_ITEM 5
|
||||||
|
#else
|
||||||
|
#define ENCODER_STEPS_PER_MENU_ITEM 2 // VIKI LCD rotary encoder uses a different number of steps per rotation
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/* Helper macros for menus */
|
/* Helper macros for menus */
|
||||||
#define START_MENU() do { \
|
#define START_MENU() do { \
|
||||||
|
@ -112,14 +119,18 @@ static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned l
|
||||||
} } while(0)
|
} } while(0)
|
||||||
|
|
||||||
/** Used variables to keep track of the menu */
|
/** Used variables to keep track of the menu */
|
||||||
|
#ifndef REPRAPWORLD_KEYPAD
|
||||||
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
||||||
|
#else
|
||||||
|
volatile uint16_t buttons;//Contains the bits of the currently pressed buttons (extended).
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
||||||
uint32_t blocking_enc;
|
uint32_t blocking_enc;
|
||||||
uint8_t lastEncoderBits;
|
uint8_t lastEncoderBits;
|
||||||
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
||||||
uint32_t encoderPosition;
|
uint32_t encoderPosition;
|
||||||
#if (SDCARDDETECT > -1)
|
#if (SDCARDDETECT > 0)
|
||||||
bool lcd_oldcardstatus;
|
bool lcd_oldcardstatus;
|
||||||
#endif
|
#endif
|
||||||
#endif//ULTIPANEL
|
#endif//ULTIPANEL
|
||||||
|
@ -157,10 +168,34 @@ static void lcd_status_screen()
|
||||||
if (LCD_CLICKED)
|
if (LCD_CLICKED)
|
||||||
{
|
{
|
||||||
currentMenu = lcd_main_menu;
|
currentMenu = lcd_main_menu;
|
||||||
|
encoderPosition = 0;
|
||||||
lcd_quick_feedback();
|
lcd_quick_feedback();
|
||||||
}
|
}
|
||||||
feedmultiply += int(encoderPosition);
|
|
||||||
encoderPosition = 0;
|
// Dead zone at 100% feedrate
|
||||||
|
if (feedmultiply < 100 && (feedmultiply + int(encoderPosition)) > 100 ||
|
||||||
|
feedmultiply > 100 && (feedmultiply + int(encoderPosition)) < 100)
|
||||||
|
{
|
||||||
|
encoderPosition = 0;
|
||||||
|
feedmultiply = 100;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (feedmultiply == 100 && int(encoderPosition) > ENCODER_FEEDRATE_DEADZONE)
|
||||||
|
{
|
||||||
|
feedmultiply += int(encoderPosition) - ENCODER_FEEDRATE_DEADZONE;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
else if (feedmultiply == 100 && int(encoderPosition) < -ENCODER_FEEDRATE_DEADZONE)
|
||||||
|
{
|
||||||
|
feedmultiply += int(encoderPosition) + ENCODER_FEEDRATE_DEADZONE;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
else if (feedmultiply != 100)
|
||||||
|
{
|
||||||
|
feedmultiply += int(encoderPosition);
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
|
||||||
if (feedmultiply < 10)
|
if (feedmultiply < 10)
|
||||||
feedmultiply = 10;
|
feedmultiply = 10;
|
||||||
if (feedmultiply > 999)
|
if (feedmultiply > 999)
|
||||||
|
@ -221,14 +256,14 @@ static void lcd_main_menu()
|
||||||
}else{
|
}else{
|
||||||
MENU_ITEM(submenu, MSG_CARD_MENU, lcd_sdcard_menu);
|
MENU_ITEM(submenu, MSG_CARD_MENU, lcd_sdcard_menu);
|
||||||
#if SDCARDDETECT < 1
|
#if SDCARDDETECT < 1
|
||||||
MENU_ITEM(gcode, MSG_CNG_SDCARD, PSTR("M21")); // SD-card changed by user
|
MENU_ITEM(gcode, MSG_CNG_SDCARD, PSTR("M21")); // SD-card changed by user
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}else{
|
}else{
|
||||||
MENU_ITEM(submenu, MSG_NO_CARD, lcd_sdcard_menu);
|
MENU_ITEM(submenu, MSG_NO_CARD, lcd_sdcard_menu);
|
||||||
#if SDCARDDETECT < 1
|
#if SDCARDDETECT < 1
|
||||||
MENU_ITEM(gcode, MSG_INIT_SDCARD, PSTR("M21")); // Manually initialize the SD-card via user interface
|
MENU_ITEM(gcode, MSG_INIT_SDCARD, PSTR("M21")); // Manually initialize the SD-card via user interface
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
END_MENU();
|
END_MENU();
|
||||||
|
@ -251,6 +286,7 @@ void lcd_preheat_pla()
|
||||||
setTargetBed(plaPreheatHPBTemp);
|
setTargetBed(plaPreheatHPBTemp);
|
||||||
fanSpeed = plaPreheatFanSpeed;
|
fanSpeed = plaPreheatFanSpeed;
|
||||||
lcd_return_to_status();
|
lcd_return_to_status();
|
||||||
|
setWatch(); // heater sanity check timer
|
||||||
}
|
}
|
||||||
|
|
||||||
void lcd_preheat_abs()
|
void lcd_preheat_abs()
|
||||||
|
@ -261,6 +297,16 @@ void lcd_preheat_abs()
|
||||||
setTargetBed(absPreheatHPBTemp);
|
setTargetBed(absPreheatHPBTemp);
|
||||||
fanSpeed = absPreheatFanSpeed;
|
fanSpeed = absPreheatFanSpeed;
|
||||||
lcd_return_to_status();
|
lcd_return_to_status();
|
||||||
|
setWatch(); // heater sanity check timer
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_cooldown()
|
||||||
|
{
|
||||||
|
setTargetHotend0(0);
|
||||||
|
setTargetHotend1(0);
|
||||||
|
setTargetHotend2(0);
|
||||||
|
setTargetBed(0);
|
||||||
|
lcd_return_to_status();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void lcd_tune_menu()
|
static void lcd_tune_menu()
|
||||||
|
@ -298,7 +344,7 @@ static void lcd_prepare_menu()
|
||||||
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
|
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
|
||||||
MENU_ITEM(function, MSG_PREHEAT_PLA, lcd_preheat_pla);
|
MENU_ITEM(function, MSG_PREHEAT_PLA, lcd_preheat_pla);
|
||||||
MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs);
|
MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs);
|
||||||
MENU_ITEM(gcode, MSG_COOLDOWN, PSTR("M104 S0\nM140 S0"));
|
MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown);
|
||||||
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
|
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
@ -459,10 +505,10 @@ static void lcd_control_menu()
|
||||||
|
|
||||||
static void lcd_control_temperature_menu()
|
static void lcd_control_temperature_menu()
|
||||||
{
|
{
|
||||||
// set up temp variables - undo the default scaling
|
// set up temp variables - undo the default scaling
|
||||||
raw_Ki = unscalePID_i(Ki);
|
raw_Ki = unscalePID_i(Ki);
|
||||||
raw_Kd = unscalePID_d(Kd);
|
raw_Kd = unscalePID_d(Kd);
|
||||||
|
|
||||||
START_MENU();
|
START_MENU();
|
||||||
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
||||||
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
@ -484,7 +530,7 @@ static void lcd_control_temperature_menu()
|
||||||
#endif
|
#endif
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
MENU_ITEM_EDIT(float52, MSG_PID_P, &Kp, 1, 9990);
|
MENU_ITEM_EDIT(float52, MSG_PID_P, &Kp, 1, 9990);
|
||||||
// i is typically a small value so allows values below 1
|
// i is typically a small value so allows values below 1
|
||||||
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I, &raw_Ki, 0.01, 9990, copy_and_scalePID_i);
|
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I, &raw_Ki, 0.01, 9990, copy_and_scalePID_i);
|
||||||
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D, &raw_Kd, 1, 9990, copy_and_scalePID_d);
|
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D, &raw_Kd, 1, 9990, copy_and_scalePID_d);
|
||||||
# ifdef PID_ADD_EXTRUSION_RATE
|
# ifdef PID_ADD_EXTRUSION_RATE
|
||||||
|
@ -687,6 +733,24 @@ menu_edit_type(float, float51, ftostr51, 10)
|
||||||
menu_edit_type(float, float52, ftostr52, 100)
|
menu_edit_type(float, float52, ftostr52, 100)
|
||||||
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
|
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
|
||||||
|
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
static void reprapworld_keypad_move_y_down() {
|
||||||
|
encoderPosition = 1;
|
||||||
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
|
lcd_move_y();
|
||||||
|
}
|
||||||
|
static void reprapworld_keypad_move_y_up() {
|
||||||
|
encoderPosition = -1;
|
||||||
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
|
lcd_move_y();
|
||||||
|
}
|
||||||
|
static void reprapworld_keypad_move_home() {
|
||||||
|
//enquecommand_P((PSTR("G28"))); // move all axis home
|
||||||
|
// TODO gregor: move all axis home, i have currently only one axis on my prusa i3
|
||||||
|
enquecommand_P((PSTR("G28 Y")));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/** End of menus **/
|
/** End of menus **/
|
||||||
|
|
||||||
static void lcd_quick_feedback()
|
static void lcd_quick_feedback()
|
||||||
|
@ -745,11 +809,20 @@ void lcd_init()
|
||||||
#ifdef NEWPANEL
|
#ifdef NEWPANEL
|
||||||
pinMode(BTN_EN1,INPUT);
|
pinMode(BTN_EN1,INPUT);
|
||||||
pinMode(BTN_EN2,INPUT);
|
pinMode(BTN_EN2,INPUT);
|
||||||
pinMode(BTN_ENC,INPUT);
|
|
||||||
pinMode(SDCARDDETECT,INPUT);
|
pinMode(SDCARDDETECT,INPUT);
|
||||||
WRITE(BTN_EN1,HIGH);
|
WRITE(BTN_EN1,HIGH);
|
||||||
WRITE(BTN_EN2,HIGH);
|
WRITE(BTN_EN2,HIGH);
|
||||||
|
#if BTN_ENC > 0
|
||||||
|
pinMode(BTN_ENC,INPUT);
|
||||||
WRITE(BTN_ENC,HIGH);
|
WRITE(BTN_ENC,HIGH);
|
||||||
|
#endif
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
pinMode(SHIFT_CLK,OUTPUT);
|
||||||
|
pinMode(SHIFT_LD,OUTPUT);
|
||||||
|
pinMode(SHIFT_OUT,INPUT);
|
||||||
|
WRITE(SHIFT_OUT,HIGH);
|
||||||
|
WRITE(SHIFT_LD,HIGH);
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
pinMode(SHIFT_CLK,OUTPUT);
|
pinMode(SHIFT_CLK,OUTPUT);
|
||||||
pinMode(SHIFT_LD,OUTPUT);
|
pinMode(SHIFT_LD,OUTPUT);
|
||||||
|
@ -759,12 +832,14 @@ void lcd_init()
|
||||||
WRITE(SHIFT_LD,HIGH);
|
WRITE(SHIFT_LD,HIGH);
|
||||||
WRITE(SHIFT_EN,LOW);
|
WRITE(SHIFT_EN,LOW);
|
||||||
#endif//!NEWPANEL
|
#endif//!NEWPANEL
|
||||||
#if (SDCARDDETECT > -1)
|
#if (SDCARDDETECT > 0)
|
||||||
WRITE(SDCARDDETECT, HIGH);
|
WRITE(SDCARDDETECT, HIGH);
|
||||||
lcd_oldcardstatus = IS_SD_INSERTED;
|
lcd_oldcardstatus = IS_SD_INSERTED;
|
||||||
#endif//(SDCARDDETECT > -1)
|
#endif//(SDCARDDETECT > 0)
|
||||||
lcd_buttons_update();
|
lcd_buttons_update();
|
||||||
|
#ifdef ULTIPANEL
|
||||||
encoderDiff = 0;
|
encoderDiff = 0;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void lcd_update()
|
void lcd_update()
|
||||||
|
@ -773,7 +848,11 @@ void lcd_update()
|
||||||
|
|
||||||
lcd_buttons_update();
|
lcd_buttons_update();
|
||||||
|
|
||||||
#if (SDCARDDETECT > -1)
|
#ifdef LCD_HAS_SLOW_BUTTONS
|
||||||
|
buttons |= lcd_implementation_read_slow_buttons(); // buttons which take too long to read in interrupt context
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if (SDCARDDETECT > 0)
|
||||||
if((IS_SD_INSERTED != lcd_oldcardstatus))
|
if((IS_SD_INSERTED != lcd_oldcardstatus))
|
||||||
{
|
{
|
||||||
lcdDrawUpdate = 2;
|
lcdDrawUpdate = 2;
|
||||||
|
@ -796,6 +875,17 @@ void lcd_update()
|
||||||
if (lcd_next_update_millis < millis())
|
if (lcd_next_update_millis < millis())
|
||||||
{
|
{
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) {
|
||||||
|
reprapworld_keypad_move_y_down();
|
||||||
|
}
|
||||||
|
if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) {
|
||||||
|
reprapworld_keypad_move_y_up();
|
||||||
|
}
|
||||||
|
if (REPRAPWORLD_KEYPAD_MOVE_HOME) {
|
||||||
|
reprapworld_keypad_move_home();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
if (encoderDiff)
|
if (encoderDiff)
|
||||||
{
|
{
|
||||||
lcdDrawUpdate = 1;
|
lcdDrawUpdate = 1;
|
||||||
|
@ -808,21 +898,26 @@ void lcd_update()
|
||||||
#endif//ULTIPANEL
|
#endif//ULTIPANEL
|
||||||
|
|
||||||
#ifdef DOGLCD // Changes due to different driver architecture of the DOGM display
|
#ifdef DOGLCD // Changes due to different driver architecture of the DOGM display
|
||||||
blink++; // Variable for fan animation and alive dot
|
blink++; // Variable for fan animation and alive dot
|
||||||
u8g.firstPage();
|
u8g.firstPage();
|
||||||
do {
|
do
|
||||||
u8g.setFont(u8g_font_6x10_marlin);
|
{
|
||||||
u8g.setPrintPos(125,0);
|
u8g.setFont(u8g_font_6x10_marlin);
|
||||||
if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot
|
u8g.setPrintPos(125,0);
|
||||||
u8g.drawPixel(127,63); // draw alive dot
|
if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot
|
||||||
u8g.setColorIndex(1); // black on white
|
u8g.drawPixel(127,63); // draw alive dot
|
||||||
(*currentMenu)();
|
u8g.setColorIndex(1); // black on white
|
||||||
if (!lcdDrawUpdate) break; // Terminate display update, when nothing new to draw. This must be done before the last dogm.next()
|
(*currentMenu)();
|
||||||
} while( u8g.nextPage() );
|
if (!lcdDrawUpdate) break; // Terminate display update, when nothing new to draw. This must be done before the last dogm.next()
|
||||||
|
} while( u8g.nextPage() );
|
||||||
#else
|
#else
|
||||||
(*currentMenu)();
|
(*currentMenu)();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef LCD_HAS_STATUS_INDICATORS
|
||||||
|
lcd_implementation_update_indicators();
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
if(timeoutToStatus < millis() && currentMenu != lcd_status_screen)
|
if(timeoutToStatus < millis() && currentMenu != lcd_status_screen)
|
||||||
{
|
{
|
||||||
|
@ -873,8 +968,24 @@ void lcd_buttons_update()
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
||||||
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
||||||
|
#if BTN_ENC > 0
|
||||||
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
|
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
|
||||||
newbutton |= EN_C;
|
newbutton |= EN_C;
|
||||||
|
#endif
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
// for the reprapworld_keypad
|
||||||
|
uint8_t newbutton_reprapworld_keypad=0;
|
||||||
|
WRITE(SHIFT_LD,LOW);
|
||||||
|
WRITE(SHIFT_LD,HIGH);
|
||||||
|
for(int8_t i=0;i<8;i++) {
|
||||||
|
newbutton_reprapworld_keypad = newbutton_reprapworld_keypad>>1;
|
||||||
|
if(READ(SHIFT_OUT))
|
||||||
|
newbutton_reprapworld_keypad|=(1<<7);
|
||||||
|
WRITE(SHIFT_CLK,HIGH);
|
||||||
|
WRITE(SHIFT_CLK,LOW);
|
||||||
|
}
|
||||||
|
newbutton |= ((~newbutton_reprapworld_keypad) << REPRAPWORLD_BTN_OFFSET); //invert it, because a pressed switch produces a logical 0
|
||||||
|
#endif
|
||||||
buttons = newbutton;
|
buttons = newbutton;
|
||||||
#else //read it from the shift register
|
#else //read it from the shift register
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
|
@ -930,6 +1041,18 @@ void lcd_buttons_update()
|
||||||
}
|
}
|
||||||
lastEncoderBits = enc;
|
lastEncoderBits = enc;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void lcd_buzz(long duration, uint16_t freq)
|
||||||
|
{
|
||||||
|
#ifdef LCD_USE_I2C_BUZZER
|
||||||
|
lcd.buzz(duration,freq);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
bool lcd_clicked()
|
||||||
|
{
|
||||||
|
return LCD_CLICKED;
|
||||||
|
}
|
||||||
#endif//ULTIPANEL
|
#endif//ULTIPANEL
|
||||||
|
|
||||||
/********************************/
|
/********************************/
|
||||||
|
@ -1131,7 +1254,7 @@ void copy_and_scalePID_i()
|
||||||
{
|
{
|
||||||
Ki = scalePID_i(raw_Ki);
|
Ki = scalePID_i(raw_Ki);
|
||||||
updatePID();
|
updatePID();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Callback for after editing PID d value
|
// Callback for after editing PID d value
|
||||||
// grab the pid d value out of the temp variable; scale it; then update the PID driver
|
// grab the pid d value out of the temp variable; scale it; then update the PID driver
|
||||||
|
@ -1139,6 +1262,6 @@ void copy_and_scalePID_d()
|
||||||
{
|
{
|
||||||
Kd = scalePID_d(raw_Kd);
|
Kd = scalePID_d(raw_Kd);
|
||||||
updatePID();
|
updatePID();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //ULTRA_LCD
|
#endif //ULTRA_LCD
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
|
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
void lcd_buttons_update();
|
void lcd_buttons_update();
|
||||||
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
|
||||||
#else
|
#else
|
||||||
FORCE_INLINE void lcd_buttons_update() {}
|
FORCE_INLINE void lcd_buttons_update() {}
|
||||||
#endif
|
#endif
|
||||||
|
@ -35,25 +34,8 @@
|
||||||
extern int absPreheatHPBTemp;
|
extern int absPreheatHPBTemp;
|
||||||
extern int absPreheatFanSpeed;
|
extern int absPreheatFanSpeed;
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
void lcd_buzz(long duration,uint16_t freq);
|
||||||
#define EN_C (1<<BLEN_C)
|
bool lcd_clicked();
|
||||||
#define EN_B (1<<BLEN_B)
|
|
||||||
#define EN_A (1<<BLEN_A)
|
|
||||||
|
|
||||||
#define LCD_CLICKED (buttons&EN_C)
|
|
||||||
#else
|
|
||||||
//atomatic, do not change
|
|
||||||
#define B_LE (1<<BL_LE)
|
|
||||||
#define B_UP (1<<BL_UP)
|
|
||||||
#define B_MI (1<<BL_MI)
|
|
||||||
#define B_DW (1<<BL_DW)
|
|
||||||
#define B_RI (1<<BL_RI)
|
|
||||||
#define B_ST (1<<BL_ST)
|
|
||||||
#define EN_B (1<<BLEN_B)
|
|
||||||
#define EN_A (1<<BLEN_A)
|
|
||||||
|
|
||||||
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
|
|
||||||
#endif//NEWPANEL
|
|
||||||
|
|
||||||
#else //no lcd
|
#else //no lcd
|
||||||
FORCE_INLINE void lcd_update() {}
|
FORCE_INLINE void lcd_update() {}
|
||||||
|
@ -61,6 +43,7 @@
|
||||||
FORCE_INLINE void lcd_setstatus(const char* message) {}
|
FORCE_INLINE void lcd_setstatus(const char* message) {}
|
||||||
FORCE_INLINE void lcd_buttons_update() {}
|
FORCE_INLINE void lcd_buttons_update() {}
|
||||||
FORCE_INLINE void lcd_reset_alert_level() {}
|
FORCE_INLINE void lcd_reset_alert_level() {}
|
||||||
|
FORCE_INLINE void lcd_buzz(long duration,uint16_t freq) {}
|
||||||
|
|
||||||
#define LCD_MESSAGEPGM(x)
|
#define LCD_MESSAGEPGM(x)
|
||||||
#define LCD_ALERTMESSAGEPGM(x)
|
#define LCD_ALERTMESSAGEPGM(x)
|
||||||
|
|
|
@ -6,10 +6,11 @@
|
||||||
* When selecting the rusian language, a slightly different LCD implementation is used to handle UTF8 characters.
|
* When selecting the rusian language, a slightly different LCD implementation is used to handle UTF8 characters.
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#if LANGUAGE_CHOICE == 6
|
#ifndef REPRAPWORLD_KEYPAD
|
||||||
#include "LiquidCrystalRus.h"
|
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
||||||
#define LCD_CLASS LiquidCrystalRus
|
|
||||||
#else
|
#else
|
||||||
|
extern volatile uint16_t buttons; //an extended version of the last checked buttons in a bit array.
|
||||||
|
|
||||||
#ifdef LCD_I2C_TYPE_PCA8574
|
#ifdef LCD_I2C_TYPE_PCA8574
|
||||||
#include <LiquidCrystal_I2C.h>
|
#include <LiquidCrystal_I2C.h>
|
||||||
#define LCD_CLASS LiquidCrystal_I2C
|
#define LCD_CLASS LiquidCrystal_I2C
|
||||||
|
@ -19,6 +20,187 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
////////////////////////////////////
|
||||||
|
// Setup button and encode mappings for each panel (into 'buttons' variable)
|
||||||
|
//
|
||||||
|
// This is just to map common functions (across different panels) onto the same
|
||||||
|
// macro name. The mapping is independent of whether the button is directly connected or
|
||||||
|
// via a shift/i2c register.
|
||||||
|
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
// All Ultipanels might have an encoder - so this is always be mapped onto first two bits
|
||||||
|
#define BLEN_B 1
|
||||||
|
#define BLEN_A 0
|
||||||
|
|
||||||
|
#define EN_B (1<<BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
|
||||||
|
#define EN_A (1<<BLEN_A)
|
||||||
|
|
||||||
|
#if defined(BTN_ENC) && BTN_ENC > -1
|
||||||
|
// encoder click is directly connected
|
||||||
|
#define BLEN_C 2
|
||||||
|
#define EN_C (1<<BLEN_C)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Setup other button mappings of each panel
|
||||||
|
//
|
||||||
|
#if defined(LCD_I2C_VIKI)
|
||||||
|
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
||||||
|
|
||||||
|
// button and encoder bit positions within 'buttons'
|
||||||
|
#define B_LE (BUTTON_LEFT<<B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C
|
||||||
|
#define B_UP (BUTTON_UP<<B_I2C_BTN_OFFSET)
|
||||||
|
#define B_MI (BUTTON_SELECT<<B_I2C_BTN_OFFSET)
|
||||||
|
#define B_DW (BUTTON_DOWN<<B_I2C_BTN_OFFSET)
|
||||||
|
#define B_RI (BUTTON_RIGHT<<B_I2C_BTN_OFFSET)
|
||||||
|
|
||||||
|
#if defined(BTN_ENC) && BTN_ENC > -1
|
||||||
|
// the pause/stop/restart button is connected to BTN_ENC when used
|
||||||
|
#define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name
|
||||||
|
#define LCD_CLICKED (buttons&(B_MI|B_RI|B_ST)) // pause/stop button also acts as click until we implement proper pause/stop.
|
||||||
|
#else
|
||||||
|
#define LCD_CLICKED (buttons&(B_MI|B_RI))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
|
||||||
|
#define LCD_HAS_SLOW_BUTTONS
|
||||||
|
|
||||||
|
#elif defined(LCD_I2C_PANELOLU2)
|
||||||
|
// encoder click can be read through I2C if not directly connected
|
||||||
|
#if BTN_ENC <= 0
|
||||||
|
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
||||||
|
|
||||||
|
#define B_MI (PANELOLU2_ENCODER_C<<B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later
|
||||||
|
|
||||||
|
#define LCD_CLICKED (buttons&B_MI)
|
||||||
|
|
||||||
|
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
|
||||||
|
#define LCD_HAS_SLOW_BUTTONS
|
||||||
|
#else
|
||||||
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#elif defined(REPRAPWORLD_KEYPAD)
|
||||||
|
// define register bit values, don't change it
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_F3 0
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_F2 1
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_F1 2
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_UP 3
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_RIGHT 4
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_MIDDLE 5
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_DOWN 6
|
||||||
|
#define BLEN_REPRAPWORLD_KEYPAD_LEFT 7
|
||||||
|
|
||||||
|
#define REPRAPWORLD_BTN_OFFSET 3 // bit offset into buttons for shift register values
|
||||||
|
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<(BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<(BLEN_REPRAPWORLD_KEYPAD_F2+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<(BLEN_REPRAPWORLD_KEYPAD_F1+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_UP (1<<(BLEN_REPRAPWORLD_KEYPAD_UP+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<(BLEN_REPRAPWORLD_KEYPAD_RIGHT+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<(BLEN_REPRAPWORLD_KEYPAD_MIDDLE+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<(BLEN_REPRAPWORLD_KEYPAD_DOWN+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<(BLEN_REPRAPWORLD_KEYPAD_LEFT+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
|
||||||
|
#define LCD_CLICKED ((buttons&EN_C) || (buttons&EN_REPRAPWORLD_KEYPAD_F1))
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons&EN_REPRAPWORLD_KEYPAD_DOWN)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons&EN_REPRAPWORLD_KEYPAD_UP)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons&EN_REPRAPWORLD_KEYPAD_MIDDLE)
|
||||||
|
|
||||||
|
#elif defined(NEWPANEL)
|
||||||
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
|
|
||||||
|
#else // old style ULTIPANEL
|
||||||
|
//bits in the shift register that carry the buttons for:
|
||||||
|
// left up center down right red(stop)
|
||||||
|
#define BL_LE 7
|
||||||
|
#define BL_UP 6
|
||||||
|
#define BL_MI 5
|
||||||
|
#define BL_DW 4
|
||||||
|
#define BL_RI 3
|
||||||
|
#define BL_ST 2
|
||||||
|
|
||||||
|
//automatic, do not change
|
||||||
|
#define B_LE (1<<BL_LE)
|
||||||
|
#define B_UP (1<<BL_UP)
|
||||||
|
#define B_MI (1<<BL_MI)
|
||||||
|
#define B_DW (1<<BL_DW)
|
||||||
|
#define B_RI (1<<BL_RI)
|
||||||
|
#define B_ST (1<<BL_ST)
|
||||||
|
|
||||||
|
#define LCD_CLICKED (buttons&(B_MI|B_ST))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
////////////////////////
|
||||||
|
// Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement)
|
||||||
|
// These values are independent of which pins are used for EN_A and EN_B indications
|
||||||
|
// The rotary encoder part is also independent to the chipset used for the LCD
|
||||||
|
#if defined(EN_A) && defined(EN_B)
|
||||||
|
#ifndef ULTIMAKERCONTROLLER
|
||||||
|
#define encrot0 0
|
||||||
|
#define encrot1 2
|
||||||
|
#define encrot2 3
|
||||||
|
#define encrot3 1
|
||||||
|
#else
|
||||||
|
#define encrot0 0
|
||||||
|
#define encrot1 1
|
||||||
|
#define encrot2 3
|
||||||
|
#define encrot3 2
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif //ULTIPANEL
|
||||||
|
|
||||||
|
////////////////////////////////////
|
||||||
|
// Create LCD class instance and chipset-specific information
|
||||||
|
#if defined(LCD_I2C_TYPE_PCF8575)
|
||||||
|
// note: these are register mapped pins on the PCF8575 controller not Arduino pins
|
||||||
|
#define LCD_I2C_PIN_BL 3
|
||||||
|
#define LCD_I2C_PIN_EN 2
|
||||||
|
#define LCD_I2C_PIN_RW 1
|
||||||
|
#define LCD_I2C_PIN_RS 0
|
||||||
|
#define LCD_I2C_PIN_D4 4
|
||||||
|
#define LCD_I2C_PIN_D5 5
|
||||||
|
#define LCD_I2C_PIN_D6 6
|
||||||
|
#define LCD_I2C_PIN_D7 7
|
||||||
|
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <LCD.h>
|
||||||
|
#include <LiquidCrystal_I2C.h>
|
||||||
|
#define LCD_CLASS LiquidCrystal_I2C
|
||||||
|
LCD_CLASS lcd(LCD_I2C_ADDRESS,LCD_I2C_PIN_EN,LCD_I2C_PIN_RW,LCD_I2C_PIN_RS,LCD_I2C_PIN_D4,LCD_I2C_PIN_D5,LCD_I2C_PIN_D6,LCD_I2C_PIN_D7);
|
||||||
|
|
||||||
|
#elif defined(LCD_I2C_TYPE_MCP23017)
|
||||||
|
//for the LED indicators (which maybe mapped to different things in lcd_implementation_update_indicators())
|
||||||
|
#define LED_A 0x04 //100
|
||||||
|
#define LED_B 0x02 //010
|
||||||
|
#define LED_C 0x01 //001
|
||||||
|
|
||||||
|
#define LCD_HAS_STATUS_INDICATORS
|
||||||
|
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <LiquidTWI2.h>
|
||||||
|
#define LCD_CLASS LiquidTWI2
|
||||||
|
LCD_CLASS lcd(LCD_I2C_ADDRESS);
|
||||||
|
|
||||||
|
#elif defined(LCD_I2C_TYPE_MCP23008)
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <LiquidTWI2.h>
|
||||||
|
#define LCD_CLASS LiquidTWI2
|
||||||
|
LCD_CLASS lcd(LCD_I2C_ADDRESS);
|
||||||
|
|
||||||
|
#else
|
||||||
|
// Standard directly connected LCD implementations
|
||||||
|
#if LANGUAGE_CHOICE == 6
|
||||||
|
#include "LiquidCrystalRus.h"
|
||||||
|
#define LCD_CLASS LiquidCrystalRus
|
||||||
|
#else
|
||||||
|
#include <LiquidCrystal.h>
|
||||||
|
#define LCD_CLASS LiquidCrystal
|
||||||
|
#endif
|
||||||
|
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Custom characters defined in the first 8 characters of the LCD */
|
/* Custom characters defined in the first 8 characters of the LCD */
|
||||||
#define LCD_STR_BEDTEMP "\x00"
|
#define LCD_STR_BEDTEMP "\x00"
|
||||||
#define LCD_STR_DEGREE "\x01"
|
#define LCD_STR_DEGREE "\x01"
|
||||||
|
@ -125,8 +307,27 @@ static void lcd_implementation_init()
|
||||||
lcd.init();
|
lcd.init();
|
||||||
lcd.backlight();
|
lcd.backlight();
|
||||||
#else
|
#else
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
if defined(LCDI2C_TYPE_PCF8575)
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef LCD_I2C_PIN_BL
|
||||||
|
lcd.setBacklightPin(LCD_I2C_PIN_BL,POSITIVE);
|
||||||
|
lcd.setBacklight(HIGH);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#elif defined(LCD_I2C_TYPE_MCP23017)
|
||||||
|
lcd.setMCPType(LTI_TYPE_MCP23017);
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
|
lcd.setBacklight(0); //set all the LEDs off to begin with
|
||||||
|
|
||||||
|
#elif defined(LCD_I2C_TYPE_MCP23008)
|
||||||
|
lcd.setMCPType(LTI_TYPE_MCP23008);
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
|
|
||||||
|
#else
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
|
#endif
|
||||||
|
|
||||||
lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp);
|
lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp);
|
||||||
lcd.createChar(LCD_STR_DEGREE[0], degree);
|
lcd.createChar(LCD_STR_DEGREE[0], degree);
|
||||||
lcd.createChar(LCD_STR_THERMOMETER[0], thermometer);
|
lcd.createChar(LCD_STR_THERMOMETER[0], thermometer);
|
||||||
|
@ -314,13 +515,13 @@ static void lcd_implementation_drawmenu_generic(uint8_t row, const char* pstr, c
|
||||||
char c;
|
char c;
|
||||||
//Use all characters in narrow LCDs
|
//Use all characters in narrow LCDs
|
||||||
#if LCD_WIDTH < 20
|
#if LCD_WIDTH < 20
|
||||||
uint8_t n = LCD_WIDTH - 1 - 1;
|
uint8_t n = LCD_WIDTH - 1 - 1;
|
||||||
#else
|
#else
|
||||||
uint8_t n = LCD_WIDTH - 1 - 2;
|
uint8_t n = LCD_WIDTH - 1 - 2;
|
||||||
#endif
|
#endif
|
||||||
lcd.setCursor(0, row);
|
lcd.setCursor(0, row);
|
||||||
lcd.print(pre_char);
|
lcd.print(pre_char);
|
||||||
while((c = pgm_read_byte(pstr)) != '\0')
|
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
pstr++;
|
pstr++;
|
||||||
|
@ -336,13 +537,13 @@ static void lcd_implementation_drawmenu_setting_edit_generic(uint8_t row, const
|
||||||
char c;
|
char c;
|
||||||
//Use all characters in narrow LCDs
|
//Use all characters in narrow LCDs
|
||||||
#if LCD_WIDTH < 20
|
#if LCD_WIDTH < 20
|
||||||
uint8_t n = LCD_WIDTH - 1 - 1 - strlen(data);
|
uint8_t n = LCD_WIDTH - 1 - 1 - strlen(data);
|
||||||
#else
|
#else
|
||||||
uint8_t n = LCD_WIDTH - 1 - 2 - strlen(data);
|
uint8_t n = LCD_WIDTH - 1 - 2 - strlen(data);
|
||||||
#endif
|
#endif
|
||||||
lcd.setCursor(0, row);
|
lcd.setCursor(0, row);
|
||||||
lcd.print(pre_char);
|
lcd.print(pre_char);
|
||||||
while((c = pgm_read_byte(pstr)) != '\0')
|
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
pstr++;
|
pstr++;
|
||||||
|
@ -358,13 +559,13 @@ static void lcd_implementation_drawmenu_setting_edit_generic_P(uint8_t row, cons
|
||||||
char c;
|
char c;
|
||||||
//Use all characters in narrow LCDs
|
//Use all characters in narrow LCDs
|
||||||
#if LCD_WIDTH < 20
|
#if LCD_WIDTH < 20
|
||||||
uint8_t n = LCD_WIDTH - 1 - 1 - strlen_P(data);
|
uint8_t n = LCD_WIDTH - 1 - 1 - strlen_P(data);
|
||||||
#else
|
#else
|
||||||
uint8_t n = LCD_WIDTH - 1 - 2 - strlen_P(data);
|
uint8_t n = LCD_WIDTH - 1 - 2 - strlen_P(data);
|
||||||
#endif
|
#endif
|
||||||
lcd.setCursor(0, row);
|
lcd.setCursor(0, row);
|
||||||
lcd.print(pre_char);
|
lcd.print(pre_char);
|
||||||
while((c = pgm_read_byte(pstr)) != '\0')
|
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
pstr++;
|
pstr++;
|
||||||
|
@ -417,9 +618,9 @@ void lcd_implementation_drawedit(const char* pstr, char* value)
|
||||||
lcd_printPGM(pstr);
|
lcd_printPGM(pstr);
|
||||||
lcd.print(':');
|
lcd.print(':');
|
||||||
#if LCD_WIDTH < 20
|
#if LCD_WIDTH < 20
|
||||||
lcd.setCursor(LCD_WIDTH - strlen(value), 1);
|
lcd.setCursor(LCD_WIDTH - strlen(value), 1);
|
||||||
#else
|
#else
|
||||||
lcd.setCursor(LCD_WIDTH -1 - strlen(value), 1);
|
lcd.setCursor(LCD_WIDTH -1 - strlen(value), 1);
|
||||||
#endif
|
#endif
|
||||||
lcd.print(value);
|
lcd.print(value);
|
||||||
}
|
}
|
||||||
|
@ -434,7 +635,7 @@ static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char*
|
||||||
filename = longFilename;
|
filename = longFilename;
|
||||||
longFilename[LCD_WIDTH-1] = '\0';
|
longFilename[LCD_WIDTH-1] = '\0';
|
||||||
}
|
}
|
||||||
while((c = *filename) != '\0')
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
filename++;
|
filename++;
|
||||||
|
@ -454,7 +655,7 @@ static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, co
|
||||||
filename = longFilename;
|
filename = longFilename;
|
||||||
longFilename[LCD_WIDTH-1] = '\0';
|
longFilename[LCD_WIDTH-1] = '\0';
|
||||||
}
|
}
|
||||||
while((c = *filename) != '\0')
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
filename++;
|
filename++;
|
||||||
|
@ -475,7 +676,7 @@ static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const
|
||||||
filename = longFilename;
|
filename = longFilename;
|
||||||
longFilename[LCD_WIDTH-2] = '\0';
|
longFilename[LCD_WIDTH-2] = '\0';
|
||||||
}
|
}
|
||||||
while((c = *filename) != '\0')
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
filename++;
|
filename++;
|
||||||
|
@ -496,7 +697,7 @@ static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pst
|
||||||
filename = longFilename;
|
filename = longFilename;
|
||||||
longFilename[LCD_WIDTH-2] = '\0';
|
longFilename[LCD_WIDTH-2] = '\0';
|
||||||
}
|
}
|
||||||
while((c = *filename) != '\0')
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
lcd.print(c);
|
lcd.print(c);
|
||||||
filename++;
|
filename++;
|
||||||
|
@ -516,15 +717,50 @@ static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pst
|
||||||
|
|
||||||
static void lcd_implementation_quick_feedback()
|
static void lcd_implementation_quick_feedback()
|
||||||
{
|
{
|
||||||
#if BEEPER > -1
|
#ifdef LCD_USE_I2C_BUZZER
|
||||||
|
lcd.buzz(60,1000/6);
|
||||||
|
#elif defined(BEEPER) && BEEPER > -1
|
||||||
SET_OUTPUT(BEEPER);
|
SET_OUTPUT(BEEPER);
|
||||||
for(int8_t i=0;i<10;i++)
|
for(int8_t i=0;i<10;i++)
|
||||||
{
|
{
|
||||||
WRITE(BEEPER,HIGH);
|
WRITE(BEEPER,HIGH);
|
||||||
delay(3);
|
delay(3);
|
||||||
WRITE(BEEPER,LOW);
|
WRITE(BEEPER,LOW);
|
||||||
delay(3);
|
delay(3);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef LCD_HAS_STATUS_INDICATORS
|
||||||
|
static void lcd_implementation_update_indicators()
|
||||||
|
{
|
||||||
|
#if defined(LCD_I2C_PANELOLU2) || defined(LCD_I2C_VIKI)
|
||||||
|
//set the LEDS - referred to as backlights by the LiquidTWI2 library
|
||||||
|
static uint8_t ledsprev = 0;
|
||||||
|
uint8_t leds = 0;
|
||||||
|
if (target_temperature_bed > 0) leds |= LED_A;
|
||||||
|
if (target_temperature[0] > 0) leds |= LED_B;
|
||||||
|
if (fanSpeed) leds |= LED_C;
|
||||||
|
#if EXTRUDERS > 1
|
||||||
|
if (target_temperature[1] > 0) leds |= LED_C;
|
||||||
|
#endif
|
||||||
|
if (leds != ledsprev) {
|
||||||
|
lcd.setBacklight(leds);
|
||||||
|
ledsprev = leds;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef LCD_HAS_SLOW_BUTTONS
|
||||||
|
static uint8_t lcd_implementation_read_slow_buttons()
|
||||||
|
{
|
||||||
|
#ifdef LCD_I2C_TYPE_MCP23017
|
||||||
|
// Reading these buttons this is likely to be too slow to call inside interrupt context
|
||||||
|
// so they are called during normal lcd_update
|
||||||
|
return lcd.readButtons() << B_I2C_BTN_OFFSET;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif//ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
#endif//ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
||||||
|
|
131
Marlin/ultralcd_st7920_u8glib_rrd.h
Normal file
131
Marlin/ultralcd_st7920_u8glib_rrd.h
Normal file
|
@ -0,0 +1,131 @@
|
||||||
|
#ifndef ULCDST7920_H
|
||||||
|
#define ULCDST7920_H
|
||||||
|
|
||||||
|
#include "Marlin.h"
|
||||||
|
|
||||||
|
#ifdef U8GLIB_ST7920
|
||||||
|
|
||||||
|
//set optimization so ARDUINO optimizes this file
|
||||||
|
#pragma GCC optimize (3)
|
||||||
|
|
||||||
|
#define ST7920_CLK_PIN LCD_PINS_D4
|
||||||
|
#define ST7920_DAT_PIN LCD_PINS_ENABLE
|
||||||
|
#define ST7920_CS_PIN LCD_PINS_RS
|
||||||
|
|
||||||
|
//#define PAGE_HEIGHT 8 //128 byte frambuffer
|
||||||
|
//#define PAGE_HEIGHT 16 //256 byte frambuffer
|
||||||
|
#define PAGE_HEIGHT 32 //512 byte framebuffer
|
||||||
|
|
||||||
|
#define WIDTH 128
|
||||||
|
#define HEIGHT 64
|
||||||
|
|
||||||
|
#include <U8glib.h>
|
||||||
|
|
||||||
|
static void ST7920_SWSPI_SND_8BIT(uint8_t val)
|
||||||
|
{
|
||||||
|
uint8_t i;
|
||||||
|
for( i=0; i<8; i++ )
|
||||||
|
{
|
||||||
|
WRITE(ST7920_CLK_PIN,0);
|
||||||
|
WRITE(ST7920_DAT_PIN,val&0x80);
|
||||||
|
val<<=1;
|
||||||
|
WRITE(ST7920_CLK_PIN,1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#define ST7920_CS() {WRITE(ST7920_CS_PIN,1);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_NCS() {WRITE(ST7920_CS_PIN,0);}
|
||||||
|
#define ST7920_SET_CMD() {ST7920_SWSPI_SND_8BIT(0xf8);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_SET_DAT() {ST7920_SWSPI_SND_8BIT(0xfa);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_WRITE_BYTE(a) {ST7920_SWSPI_SND_8BIT((a)&0xf0);ST7920_SWSPI_SND_8BIT((a)<<4);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_WRITE_BYTES(p,l) {uint8_t i;for(i=0;i<l;i++){ST7920_SWSPI_SND_8BIT(*p&0xf0);ST7920_SWSPI_SND_8BIT(*p<<4);p++;}u8g_10MicroDelay();}
|
||||||
|
|
||||||
|
uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg)
|
||||||
|
{
|
||||||
|
uint8_t i,y;
|
||||||
|
switch(msg)
|
||||||
|
{
|
||||||
|
case U8G_DEV_MSG_INIT:
|
||||||
|
{
|
||||||
|
SET_OUTPUT(ST7920_CS_PIN);
|
||||||
|
WRITE(ST7920_CS_PIN,0);
|
||||||
|
SET_OUTPUT(ST7920_DAT_PIN);
|
||||||
|
WRITE(ST7920_DAT_PIN,0);
|
||||||
|
SET_OUTPUT(ST7920_CLK_PIN);
|
||||||
|
WRITE(ST7920_CLK_PIN,1);
|
||||||
|
|
||||||
|
ST7920_CS();
|
||||||
|
u8g_Delay(90); //initial delay for boot up
|
||||||
|
ST7920_SET_CMD();
|
||||||
|
ST7920_WRITE_BYTE(0x08); //display off, cursor+blink off
|
||||||
|
ST7920_WRITE_BYTE(0x01); //clear CGRAM ram
|
||||||
|
u8g_Delay(10); //delay for cgram clear
|
||||||
|
ST7920_WRITE_BYTE(0x3E); //extended mode + gdram active
|
||||||
|
for(y=0;y<HEIGHT/2;y++) //clear GDRAM
|
||||||
|
{
|
||||||
|
ST7920_WRITE_BYTE(0x80|y); //set y
|
||||||
|
ST7920_WRITE_BYTE(0x80); //set x = 0
|
||||||
|
ST7920_SET_DAT();
|
||||||
|
for(i=0;i<2*WIDTH/8;i++) //2x width clears both segments
|
||||||
|
ST7920_WRITE_BYTE(0);
|
||||||
|
ST7920_SET_CMD();
|
||||||
|
}
|
||||||
|
ST7920_WRITE_BYTE(0x0C); //display on, cursor+blink off
|
||||||
|
ST7920_NCS();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case U8G_DEV_MSG_STOP:
|
||||||
|
break;
|
||||||
|
case U8G_DEV_MSG_PAGE_NEXT:
|
||||||
|
{
|
||||||
|
uint8_t *ptr;
|
||||||
|
u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem);
|
||||||
|
y = pb->p.page_y0;
|
||||||
|
ptr = (uint8_t*)pb->buf;
|
||||||
|
|
||||||
|
ST7920_CS();
|
||||||
|
for( i = 0; i < PAGE_HEIGHT; i ++ )
|
||||||
|
{
|
||||||
|
ST7920_SET_CMD();
|
||||||
|
if ( y < 32 )
|
||||||
|
{
|
||||||
|
ST7920_WRITE_BYTE(0x80 | y); //y
|
||||||
|
ST7920_WRITE_BYTE(0x80); //x=0
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ST7920_WRITE_BYTE(0x80 | (y-32)); //y
|
||||||
|
ST7920_WRITE_BYTE(0x80 | 8); //x=64
|
||||||
|
}
|
||||||
|
|
||||||
|
ST7920_SET_DAT();
|
||||||
|
ST7920_WRITE_BYTES(ptr,WIDTH/8); //ptr is incremented inside of macro
|
||||||
|
y++;
|
||||||
|
}
|
||||||
|
ST7920_NCS();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#if PAGE_HEIGHT == 8
|
||||||
|
return u8g_dev_pb8h1_base_fn(u8g, dev, msg, arg);
|
||||||
|
#elif PAGE_HEIGHT == 16
|
||||||
|
return u8g_dev_pb16h1_base_fn(u8g, dev, msg, arg);
|
||||||
|
#else
|
||||||
|
return u8g_dev_pb32h1_base_fn(u8g, dev, msg, arg);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t u8g_dev_st7920_128x64_rrd_buf[WIDTH*(PAGE_HEIGHT/8)] U8G_NOCOMMON;
|
||||||
|
u8g_pb_t u8g_dev_st7920_128x64_rrd_pb = {{PAGE_HEIGHT,HEIGHT,0,0,0},WIDTH,u8g_dev_st7920_128x64_rrd_buf};
|
||||||
|
u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = {u8g_dev_rrd_st7920_128x64_fn,&u8g_dev_st7920_128x64_rrd_pb,&u8g_com_null_fn};
|
||||||
|
|
||||||
|
class U8GLIB_ST7920_128X64_RRD : public U8GLIB
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
U8GLIB_ST7920_128X64_RRD(uint8_t dummy) : U8GLIB(&u8g_dev_st7920_128x64_rrd_sw_spi) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif //U8GLIB_ST7920
|
||||||
|
#endif //ULCDST7920_H
|
472
README.md
472
README.md
|
@ -1,223 +1,249 @@
|
||||||
WARNING:
|
==========================
|
||||||
--------
|
Marlin 3D Printer Firmware
|
||||||
THIS IS RELEASE CANDIDATE 2 FOR MARLIN 1.0.0
|
==========================
|
||||||
|
|
||||||
The configuration is now split in two files
|
[![Flattr this git repo](http://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/ErikZalm/Marlin&title=Marlin&language=&tags=github&category=software)
|
||||||
Configuration.h for the normal settings
|
|
||||||
Configuration_adv.h for the advanced settings
|
Quick Information
|
||||||
|
===================
|
||||||
Gen7T is not supported.
|
This RepRap firmware is a mashup between <a href="https://github.com/kliment/Sprinter">Sprinter</a>, <a href="https://github.com/simen/grbl/tree">grbl</a> and many original parts.
|
||||||
|
|
||||||
Quick Information
|
Derived from Sprinter and Grbl by Erik van der Zalm.
|
||||||
===================
|
Sprinters lead developers are Kliment and caru.
|
||||||
This RepRap firmware is a mashup between <a href="https://github.com/kliment/Sprinter">Sprinter</a>, <a href="https://github.com/simen/grbl/tree">grbl</a> and many original parts.
|
Grbls lead developer is Simen Svale Skogsrud. Sonney Jeon (Chamnit) improved some parts of grbl
|
||||||
|
A fork by bkubicek for the Ultimaker was merged, and further development was aided by him.
|
||||||
Derived from Sprinter and Grbl by Erik van der Zalm.
|
Some features have been added by:
|
||||||
Sprinters lead developers are Kliment and caru.
|
Lampmaker, Bradley Feldman, and others...
|
||||||
Grbls lead developer is Simen Svale Skogsrud. Sonney Jeon (Chamnit) improved some parts of grbl
|
|
||||||
A fork by bkubicek for the Ultimaker was merged, and further development was aided by him.
|
|
||||||
Some features have been added by:
|
Features:
|
||||||
Lampmaker, Bradley Feldman, and others...
|
|
||||||
|
* Interrupt based movement with real linear acceleration
|
||||||
|
* High steprate
|
||||||
Features:
|
* Look ahead (Keep the speed high when possible. High cornering speed)
|
||||||
|
* Interrupt based temperature protection
|
||||||
* Interrupt based movement with real linear acceleration
|
* preliminary support for Matthew Roberts advance algorithm
|
||||||
* High steprate
|
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||||
* Look ahead (Keep the speed high when possible. High cornering speed)
|
* Full endstop support
|
||||||
* Interrupt based temperature protection
|
* SD Card support
|
||||||
* preliminary support for Matthew Roberts advance algorithm
|
* SD Card folders (works in pronterface)
|
||||||
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
* SD Card autostart support
|
||||||
* Full endstop support
|
* LCD support (ideally 20x4)
|
||||||
* SD Card support
|
* LCD menu system for autonomous SD card printing, controlled by an click-encoder.
|
||||||
* SD Card folders (works in pronterface)
|
* EEPROM storage of e.g. max-velocity, max-acceleration, and similar variables
|
||||||
* SD Card autostart support
|
* many small but handy things originating from bkubicek's fork.
|
||||||
* LCD support (ideally 20x4)
|
* Arc support
|
||||||
* LCD menu system for autonomous SD card printing, controlled by an click-encoder.
|
* Temperature oversampling
|
||||||
* EEPROM storage of e.g. max-velocity, max-acceleration, and similar variables
|
* Dynamic Temperature setpointing aka "AutoTemp"
|
||||||
* many small but handy things originating from bkubicek's fork.
|
* Support for QTMarlin, a very beta GUI for PID-tuning and velocity-acceleration testing. https://github.com/bkubicek/QTMarlin
|
||||||
* Arc support
|
* Endstop trigger reporting to the host software.
|
||||||
* Temperature oversampling
|
* Updated sdcardlib
|
||||||
* Dynamic Temperature setpointing aka "AutoTemp"
|
* Heater power reporting. Useful for PID monitoring.
|
||||||
* Support for QTMarlin, a very beta GUI for PID-tuning and velocity-acceleration testing. https://github.com/bkubicek/QTMarlin
|
* PID tuning
|
||||||
* Endstop trigger reporting to the host software.
|
* CoreXY kinematics (www.corexy.com/theory.html)
|
||||||
* Updated sdcardlib
|
* Configurable serial port to support connection of wireless adaptors.
|
||||||
* Heater power reporting. Useful for PID monitoring.
|
* Automatic operation of extruder/cold-end cooling fans based on nozzle temperature
|
||||||
* PID tuning
|
|
||||||
* CoreXY kinematics (www.corexy.com/theory.html)
|
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
||||||
* Configurable serial port to support connection of wireless adaptors.
|
|
||||||
|
|
||||||
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
Differences and additions to the already good Sprinter firmware:
|
||||||
|
================================================================
|
||||||
|
|
||||||
Differences and additions to the already good Sprinter firmware:
|
*Look-ahead:*
|
||||||
================================================================
|
|
||||||
|
Marlin has look-ahead. While sprinter has to break and re-accelerate at each corner,
|
||||||
*Look-ahead:*
|
lookahead will only decelerate and accelerate to a velocity,
|
||||||
|
so that the change in vectorial velocity magnitude is less than the xy_jerk_velocity.
|
||||||
Marlin has look-ahead. While sprinter has to break and re-accelerate at each corner,
|
This is only possible, if some future moves are already processed, hence the name.
|
||||||
lookahead will only decelerate and accelerate to a velocity,
|
It leads to less over-deposition at corners, especially at flat angles.
|
||||||
so that the change in vectorial velocity magnitude is less than the xy_jerk_velocity.
|
|
||||||
This is only possible, if some future moves are already processed, hence the name.
|
*Arc support:*
|
||||||
It leads to less over-deposition at corners, especially at flat angles.
|
|
||||||
|
Slic3r can find curves that, although broken into segments, were ment to describe an arc.
|
||||||
*Arc support:*
|
Marlin is able to print those arcs. The advantage is the firmware can choose the resolution,
|
||||||
|
and can perform the arc with nearly constant velocity, resulting in a nice finish.
|
||||||
Slic3r can find curves that, although broken into segments, were ment to describe an arc.
|
Also, less serial communication is needed.
|
||||||
Marlin is able to print those arcs. The advantage is the firmware can choose the resolution,
|
|
||||||
and can perform the arc with nearly constant velocity, resulting in a nice finish.
|
*Temperature Oversampling:*
|
||||||
Also, less serial communication is needed.
|
|
||||||
|
To reduce noise and make the PID-differential term more useful, 16 ADC conversion results are averaged.
|
||||||
*Temperature Oversampling:*
|
|
||||||
|
*AutoTemp:*
|
||||||
To reduce noise and make the PID-differential term more useful, 16 ADC conversion results are averaged.
|
|
||||||
|
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly.
|
||||||
*AutoTemp:*
|
Usually, higher speed requires higher temperature.
|
||||||
|
This can now be performed by the AutoTemp function
|
||||||
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly.
|
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode.
|
||||||
Usually, higher speed requires higher temperature.
|
|
||||||
This can now be performed by the AutoTemp function
|
You can leave it by calling M109 without any F.
|
||||||
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode.
|
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].
|
||||||
|
The wanted temperature then will be set to t=tempmin+factor*maxerate, while being limited between tempmin and tempmax.
|
||||||
You can leave it by calling M109 without any F.
|
If the target temperature is set manually or by gcode to a value less then tempmin, it will be kept without change.
|
||||||
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].
|
Ideally, your gcode can be completely free of temperature controls, apart from a M109 S T F in the start.gcode, and a M109 S0 in the end.gcode.
|
||||||
The wanted temperature then will be set to t=tempmin+factor*maxerate, while being limited between tempmin and tempmax.
|
|
||||||
If the target temperature is set manually or by gcode to a value less then tempmin, it will be kept without change.
|
*EEPROM:*
|
||||||
Ideally, your gcode can be completely free of temperature controls, apart from a M109 S T F in the start.gcode, and a M109 S0 in the end.gcode.
|
|
||||||
|
If you know your PID values, the acceleration and max-velocities of your unique machine, you can set them, and finally store them in the EEPROM.
|
||||||
*EEPROM:*
|
After each reboot, it will magically load them from EEPROM, independent what your Configuration.h says.
|
||||||
|
|
||||||
If you know your PID values, the acceleration and max-velocities of your unique machine, you can set them, and finally store them in the EEPROM.
|
*LCD Menu:*
|
||||||
After each reboot, it will magically load them from EEPROM, independent what your Configuration.h says.
|
|
||||||
|
If your hardware supports it, you can build yourself a LCD-CardReader+Click+encoder combination. It will enable you to realtime tune temperatures,
|
||||||
*LCD Menu:*
|
accelerations, velocities, flow rates, select and print files from the SD card, preheat, disable the steppers, and do other fancy stuff.
|
||||||
|
One working hardware is documented here: http://www.thingiverse.com/thing:12663
|
||||||
If your hardware supports it, you can build yourself a LCD-CardReader+Click+encoder combination. It will enable you to realtime tune temperatures,
|
Also, with just a 20x4 or 16x2 display, useful data is shown.
|
||||||
accelerations, velocities, flow rates, select and print files from the SD card, preheat, disable the steppers, and do other fancy stuff.
|
|
||||||
One working hardware is documented here: http://www.thingiverse.com/thing:12663
|
*SD card folders:*
|
||||||
Also, with just a 20x4 or 16x2 display, useful data is shown.
|
|
||||||
|
If you have an SD card reader attached to your controller, also folders work now. Listing the files in pronterface will show "/path/subpath/file.g".
|
||||||
*SD card folders:*
|
You can write to file in a subfolder by specifying a similar text using small letters in the path.
|
||||||
|
Also, backup copies of various operating systems are hidden, as well as files not ending with ".g".
|
||||||
If you have an SD card reader attached to your controller, also folders work now. Listing the files in pronterface will show "/path/subpath/file.g".
|
|
||||||
You can write to file in a subfolder by specifying a similar text using small letters in the path.
|
*SD card folders:*
|
||||||
Also, backup copies of various operating systems are hidden, as well as files not ending with ".g".
|
|
||||||
|
If you place a file auto[0-9].g into the root of the sd card, it will be automatically executed if you boot the printer. The same file will be executed by selecting "Autostart" from the menu.
|
||||||
*SD card folders:*
|
First *0 will be performed, than *1 and so on. That way, you can heat up or even print automatically without user interaction.
|
||||||
|
|
||||||
If you place a file auto[0-9].g into the root of the sd card, it will be automatically executed if you boot the printer. The same file will be executed by selecting "Autostart" from the menu.
|
*Endstop trigger reporting:*
|
||||||
First *0 will be performed, than *1 and so on. That way, you can heat up or even print automatically without user interaction.
|
|
||||||
|
If an endstop is hit while moving towards the endstop, the location at which the firmware thinks that the endstop was triggered is outputed on the serial port.
|
||||||
*Endstop trigger reporting:*
|
This is useful, because the user gets a warning message.
|
||||||
|
However, also tools like QTMarlin can use this for finding acceptable combinations of velocity+acceleration.
|
||||||
If an endstop is hit while moving towards the endstop, the location at which the firmware thinks that the endstop was triggered is outputed on the serial port.
|
|
||||||
This is useful, because the user gets a warning message.
|
*Coding paradigm:*
|
||||||
However, also tools like QTMarlin can use this for finding acceptable combinations of velocity+acceleration.
|
|
||||||
|
Not relevant from a user side, but Marlin was split into thematic junks, and has tried to partially enforced private variables.
|
||||||
*Coding paradigm:*
|
This is intended to make it clearer, what interacts which what, and leads to a higher level of modularization.
|
||||||
|
We think that this is a useful prestep for porting this firmware to e.g. an ARM platform in the future.
|
||||||
Not relevant from a user side, but Marlin was split into thematic junks, and has tried to partially enforced private variables.
|
A lot of RAM (with enabled LCD ~2200 bytes) was saved by storing char []="some message" in Program memory.
|
||||||
This is intended to make it clearer, what interacts which what, and leads to a higher level of modularization.
|
In the serial communication, a #define based level of abstraction was enforced, so that it is clear that
|
||||||
We think that this is a useful prestep for porting this firmware to e.g. an ARM platform in the future.
|
some transfer is information (usually beginning with "echo:"), an error "error:", or just normal protocol,
|
||||||
A lot of RAM (with enabled LCD ~2200 bytes) was saved by storing char []="some message" in Program memory.
|
necessary for backwards compatibility.
|
||||||
In the serial communication, a #define based level of abstraction was enforced, so that it is clear that
|
|
||||||
some transfer is information (usually beginning with "echo:"), an error "error:", or just normal protocol,
|
*Interrupt based temperature measurements:*
|
||||||
necessary for backwards compatibility.
|
|
||||||
|
An interrupt is used to manage ADC conversions, and enforce checking for critical temperatures.
|
||||||
*Interrupt based temperature measurements:*
|
This leads to less blocking in the heater management routine.
|
||||||
|
|
||||||
An interrupt is used to manage ADC conversions, and enforce checking for critical temperatures.
|
Implemented G Codes:
|
||||||
This leads to less blocking in the heater management routine.
|
====================
|
||||||
|
|
||||||
|
* G0 -> G1
|
||||||
Non-standard M-Codes, different to an old version of sprinter:
|
* G1 - Coordinated Movement X Y Z E
|
||||||
==============================================================
|
* G2 - CW ARC
|
||||||
Movement:
|
* G3 - CCW ARC
|
||||||
|
* G4 - Dwell S<seconds> or P<milliseconds>
|
||||||
* G2 - CW ARC
|
* G10 - retract filament according to settings of M207
|
||||||
* G3 - CCW ARC
|
* G11 - retract recover filament according to settings of M208
|
||||||
|
* G28 - Home all Axis
|
||||||
General:
|
* G90 - Use Absolute Coordinates
|
||||||
|
* G91 - Use Relative Coordinates
|
||||||
* M17 - Enable/Power all stepper motors. Compatibility to ReplicatorG.
|
* G92 - Set current position to cordinates given
|
||||||
* M18 - Disable all stepper motors; same as M84.Compatibility to ReplicatorG.
|
|
||||||
* M30 - Print time since last M109 or SD card start to serial
|
RepRap M Codes
|
||||||
* M42 - Change pin status via gcode
|
* M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
|
||||||
* M80 - Turn on Power Supply
|
* M1 - Same as M0
|
||||||
* M81 - Turn off Power Supply
|
* M104 - Set extruder target temp
|
||||||
* M114 - Output current position to serial port
|
* M105 - Read current temp
|
||||||
* M119 - Output Endstop status to serial port
|
* M106 - Fan on
|
||||||
|
* M107 - Fan off
|
||||||
Movement variables:
|
* M109 - Wait for extruder current temp to reach target temp.
|
||||||
|
* M114 - Display current position
|
||||||
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
|
||||||
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
|
Custom M Codes
|
||||||
* M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
|
* M17 - Enable/Power all stepper motors
|
||||||
* M206 - set home offsets. This sets the X,Y,Z coordinates of the endstops (and is added to the {X,Y,Z}_HOME_POS configuration options (and is also added to the coordinates, if any, provided to G82, as with earlier firmware)
|
* M18 - Disable all stepper motors; same as M84
|
||||||
* M220 - set build speed mulitplying S:factor in percent ; aka "realtime tuneing in the gcode". So you can slow down if you have islands in one height-range, and speed up otherwise.
|
* M20 - List SD card
|
||||||
* M221 - set the extrude multiplying S:factor in percent
|
* M21 - Init SD card
|
||||||
* M400 - Finish all buffered moves.
|
* M22 - Release SD card
|
||||||
|
* M23 - Select SD file (M23 filename.g)
|
||||||
Temperature variables:
|
* M24 - Start/resume SD print
|
||||||
* M301 - Set PID parameters P I and D
|
* M25 - Pause SD print
|
||||||
* M302 - Allow cold extrudes
|
* M26 - Set SD position in bytes (M26 S12345)
|
||||||
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
* M27 - Report SD print status
|
||||||
|
* M28 - Start SD write (M28 filename.g)
|
||||||
Advance:
|
* M29 - Stop SD write
|
||||||
|
* M30 - Delete file from SD (M30 filename.g)
|
||||||
* M200 - Set filament diameter for advance
|
* M31 - Output time since last M109 or SD card start to serial
|
||||||
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
* M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
|
||||||
|
* M80 - Turn on Power Supply
|
||||||
EEPROM:
|
* M81 - Turn off Power Supply
|
||||||
|
* M82 - Set E codes absolute (default)
|
||||||
* M500 - stores paramters in EEPROM. This parameters are stored: axis_steps_per_unit, max_feedrate, max_acceleration ,acceleration,retract_acceleration,
|
* M83 - Set E codes relative while in Absolute Coordinates (G90) mode
|
||||||
minimumfeedrate,mintravelfeedrate,minsegmenttime, jerk velocities, PID
|
* M84 - Disable steppers until next move, or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
||||||
* M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
* M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||||
* M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
* M92 - Set axis_steps_per_unit - same syntax as G92
|
||||||
* M503 - print the current settings (from memory not from eeprom)
|
* M114 - Output current position to serial port
|
||||||
|
* M115 - Capabilities string
|
||||||
MISC:
|
* M117 - display message
|
||||||
|
* M119 - Output Endstop status to serial port
|
||||||
* M240 - Trigger a camera to take a photograph
|
* M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
|
||||||
* M999 - Restart after being stopped by error
|
* M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
|
||||||
|
* M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
||||||
Configuring and compilation:
|
* M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
||||||
============================
|
* M140 - Set bed target temp
|
||||||
|
* M190 - Wait for bed current temp to reach target temp.
|
||||||
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
* M200 - Set filament diameter
|
||||||
http://www.arduino.cc/en/Main/Software
|
* M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
||||||
|
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
||||||
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
|
||||||
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
* M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
|
||||||
|
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk
|
||||||
Install Ultimaker's RepG 25 build
|
* M206 - set additional homeing offset
|
||||||
http://software.ultimaker.com
|
* M207 - set retract length S[positive mm] F[feedrate mm/sec] Z[additional zlift/hop]
|
||||||
For SD handling and as better substitute (apart from stl manipulation) download
|
* M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
|
||||||
the very nice Kliment's printrun/pronterface https://github.com/kliment/Printrun
|
* M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
|
||||||
|
* M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
|
||||||
Copy the Ultimaker Marlin firmware
|
* M220 S<factor in percent>- set speed factor override percentage
|
||||||
https://github.com/ErikZalm/Marlin/tree/Marlin_v1
|
* M221 S<factor in percent>- set extrude factor override percentage
|
||||||
(Use the download button)
|
* M240 - Trigger a camera to take a photograph
|
||||||
|
* M280 - set servo position absolute. P: servo index, S: angle or microseconds
|
||||||
Start the arduino IDE.
|
* M300 - Play beepsound S<frequency Hz> P<duration ms>
|
||||||
Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
* M301 - Set PID parameters P I and D
|
||||||
Select the correct serial port in Tools ->Serial Port
|
* M302 - Allow cold extrudes
|
||||||
Open Marlin.pde
|
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
||||||
|
* M304 - Set bed PID parameters P I and D
|
||||||
Click the Verify/Compile button
|
* M400 - Finish all moves
|
||||||
|
* M500 - stores paramters in EEPROM
|
||||||
Click the Upload button
|
* M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||||
If all goes well the firmware is uploading
|
* M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||||
|
* M503 - print the current settings (from memory not from eeprom)
|
||||||
Start Ultimaker's Custom RepG 25
|
* M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
|
||||||
Make sure Show Experimental Profiles is enabled in Preferences
|
* M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
|
||||||
Select Sprinter as the Driver
|
* M907 - Set digital trimpot motor current using axis codes.
|
||||||
|
* M908 - Control digital trimpot directly.
|
||||||
Press the Connect button.
|
* M350 - Set microstepping mode.
|
||||||
|
* M351 - Toggle MS1 MS2 pins directly.
|
||||||
KNOWN ISSUES: RepG will display: Unknown: marlin x.y.z
|
* M928 - Start SD logging (M928 filename.g) - ended by M29
|
||||||
|
* M999 - Restart after being stopped by error
|
||||||
That's ok. Enjoy Silky Smooth Printing.
|
|
||||||
|
|
||||||
|
Configuring and compilation:
|
||||||
|
============================
|
||||||
|
|
||||||
|
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
||||||
|
http://www.arduino.cc/en/Main/Software
|
||||||
|
|
||||||
|
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
||||||
|
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
||||||
|
|
||||||
|
Copy the Marlin firmware
|
||||||
|
https://github.com/ErikZalm/Marlin/tree/Marlin_v1
|
||||||
|
(Use the download button)
|
||||||
|
|
||||||
|
Start the arduino IDE.
|
||||||
|
Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
||||||
|
Select the correct serial port in Tools ->Serial Port
|
||||||
|
Open Marlin.pde
|
||||||
|
|
||||||
|
Click the Verify/Compile button
|
||||||
|
|
||||||
|
Click the Upload button
|
||||||
|
If all goes well the firmware is uploading
|
||||||
|
|
||||||
|
That's ok. Enjoy Silky Smooth Printing.
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue