Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/bugfix-2.0.x' into X5SA-2E-Bug…
Browse files Browse the repository at this point in the history
…fix-ColorUI
  • Loading branch information
effgarces committed Oct 17, 2020
2 parents 4c31951 + 263f29a commit 81a8ec6
Show file tree
Hide file tree
Showing 300 changed files with 3,084 additions and 2,883 deletions.
1 change: 1 addition & 0 deletions .github/workflows/test-builds.yml
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ jobs:
- STM32F103RET6_creality
- LERDGEX
- mks_robin_nano35
- NUCLEO_F767ZI

# Put lengthy tests last

Expand Down
117 changes: 94 additions & 23 deletions Marlin/Configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
*
* Advanced settings can be found in Configuration_adv.h
*/
#define CONFIGURATION_H_VERSION 020007
#define CONFIGURATION_H_VERSION 020008

//===========================================================================
//============================= Getting Started =============================
Expand Down Expand Up @@ -433,6 +433,12 @@
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100

// Resistor values when using a MAX31865 (sensor -5)
// Sensor value is typically 100 (PT100) or 1000 (PT1000)
// Calibration value is typically 430 ohm for AdaFruit PT100 modules and 4300 ohm for AdaFruit PT1000 modules.
//#define MAX31865_SENSOR_OHMS 100
//#define MAX31865_CALIBRATION_OHMS 430

// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
Expand Down Expand Up @@ -2200,43 +2206,108 @@
//=============================== Graphical TFTs ==============================
//=============================================================================

/**
* Specific TFT Model Presets. Enable one of the following options
* or enable TFT_GENERIC and set sub-options.
*/

//
// TFT display with optional touch screen
// Color Marlin UI with standard menu system
// 480x320, 3.5", SPI Display From MKS
// Normally used in MKS Robin Nano V2
//
//#define TFT_320x240
//#define TFT_320x240_SPI
#define TFT_480x320
//#define TFT_480x320_SPI
//#define MKS_TS35_V2_0

//
// Skip autodetect and force specific TFT driver
// Mandatory for SPI screens with no MISO line
// Available drivers are: ST7735, ST7789, ST7796, R61505, ILI9328, ILI9341, ILI9488
// 320x240, 2.4", FSMC Display From MKS
// Normally used in MKS Robin Nano V1.2
//
//#define TFT_DRIVER AUTO
//#define MKS_ROBIN_TFT24

//
// SPI display (MKS Robin Nano V2.0, MKS Gen L V2.0)
// Upscaled 128x64 Marlin UI
// 320x240, 2.8", FSMC Display From MKS
// Normally used in MKS Robin Nano V1.2
//
//#define SPI_GRAPHICAL_TFT
//#define MKS_ROBIN_TFT28

//
// FSMC display (MKS Robin, Alfawise U20, JGAurora A5S, REXYZ A1, etc.)
// Upscaled 128x64 Marlin UI
// 320x240, 3.2", FSMC Display From MKS
// Normally used in MKS Robin Nano V1.2
//
//#define FSMC_GRAPHICAL_TFT
//#define MKS_ROBIN_TFT32

//
// TFT LVGL UI
// 480x320, 3.5", FSMC Display From MKS
// Normally used in MKS Robin Nano V1.2
//
//#define MKS_ROBIN_TFT35

//
// 480x272, 4.3", FSMC Display From MKS
//
//#define MKS_ROBIN_TFT43

//
// Using default MKS icons and fonts from: https://git.io/JJvzK
// Just copy the 'assets' folder from the build directory to the
// root of your SD card, together with the compiled firmware.
// 320x240, 3.2", FSMC Display From MKS
// Normally used in MKS Robin
//
//#define MKS_ROBIN_TFT_V1_1R

//
// 480x320, 3.5", FSMC Stock Display from TronxXY
//
#define TFT_TRONXY_X5SA

//
// 480x320, 3.5", FSMC Stock Display from AnyCubic
//
//#define ANYCUBIC_TFT35

//
//#define TFT_LVGL_UI_FSMC // Robin nano v1.2 uses FSMC
//#define TFT_LVGL_UI_SPI // Robin nano v2.0 uses SPI
// 320x240, 2.8", FSMC Stock Display from Longer/Alfawise
//
//#define LONGER_LK_TFT28

//
// Generic TFT with detailed options
//
//#define TFT_GENERIC
#if ENABLED(TFT_GENERIC)
// :[ 'AUTO', 'ST7735', 'ST7789', 'ST7796', 'R61505', 'ILI9328', 'ILI9341', 'ILI9488' ]
#define TFT_DRIVER AUTO

// Interface. Enable one of the following options:
//#define TFT_INTERFACE_FSMC
//#define TFT_INTERFACE_SPI

// TFT Resolution. Enable one of the following options:
//#define TFT_RES_320x240
//#define TFT_RES_480x272
//#define TFT_RES_480x320
#endif

/**
* TFT UI - User Interface Selection. Enable one of the following options:
*
* TFT_CLASSIC_UI - Emulated DOGM - 128x64 Upscaled
* TFT_COLOR_UI - Marlin Default Menus, Touch Friendly, using full TFT capabilities
* TFT_LVGL_UI - A Modern UI using LVGL
*
* For LVGL_UI also copy the 'assets' folder from the build directory to the
* root of your SD card, together with the compiled firmware.
*/
//#define TFT_CLASSIC_UI
#define TFT_COLOR_UI
//#define TFT_LVGL_UI

/**
* TFT Rotation. Set to one of the following values:
*
* TFT_ROTATE_90, TFT_ROTATE_90_MIRROR_X, TFT_ROTATE_90_MIRROR_Y,
* TFT_ROTATE_180, TFT_ROTATE_180_MIRROR_X, TFT_ROTATE_180_MIRROR_Y,
* TFT_ROTATE_270, TFT_ROTATE_270_MIRROR_X, TFT_ROTATE_270_MIRROR_Y,
* TFT_MIRROR_X, TFT_MIRROR_Y, TFT_NO_ROTATION
*/
//#define TFT_ROTATION TFT_NO_ROTATION

//
// Anycubic Mega TFT (AI3M)
Expand Down
38 changes: 27 additions & 11 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
*
* Basic settings can be found in Configuration.h
*/
#define CONFIGURATION_ADV_H_VERSION 020007
#define CONFIGURATION_ADV_H_VERSION 020008

//===========================================================================
//============================= Thermal Settings ============================
Expand Down Expand Up @@ -808,11 +808,9 @@
#define TRAMMING_POINT_NAME_3 "Back-Right"
#define TRAMMING_POINT_NAME_4 "Back-Left"

// Enable to restore leveling setup after operation
#define RESTORE_LEVELING_AFTER_G35
// Add a menu item for Assisted Tramming
//#define ASSISTED_TRAMMING_MENU_ITEM
#define RESTORE_LEVELING_AFTER_G35 // Enable to restore leveling setup after operation
//#define REPORT_TRAMMING_MM // Report Z deviation (mm) for each point relative to the first
//#define ASSISTED_TRAMMING_MENU_ITEM // Add a menu item for Assisted Tramming
/**
* Screw thread:
Expand Down Expand Up @@ -1050,10 +1048,10 @@

// @section lcd

#if EITHER(ULTIPANEL, EXTENSIBLE_UI)
#if EITHER(IS_ULTIPANEL, EXTENSIBLE_UI)
#define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel
#define SHORT_MANUAL_Z_MOVE 0.025 // (mm) Smallest manual Z move (< 0.1mm)
#if ENABLED(ULTIPANEL)
#if IS_ULTIPANEL
#define MANUAL_E_MOVES_RELATIVE // Display extruder move distance rather than "position"
#define ULTIPANEL_FEEDMULTIPLY // Encoder sets the feedrate multiplier on the Status Screen
#endif
Expand Down Expand Up @@ -1562,10 +1560,9 @@
#endif

//
// FSMC / SPI Graphical TFT
// Classic UI Options
//
#if TFT_SCALED_DOGLCD
//#define GRAPHICAL_TFT_ROTATE_180
//#define TFT_MARLINUI_COLOR 0xFFFF // White
//#define TFT_MARLINBG_COLOR 0x0000 // Black
//#define TFT_DISABLED_COLOR 0x0003 // Almost black
Expand Down Expand Up @@ -2961,7 +2958,7 @@
* This allows the laser to keep in perfect sync with the planner and removes
* the powerup/down delay since lasers require negligible time.
*/
#define LASER_POWER_INLINE
//#define LASER_POWER_INLINE

#if ENABLED(LASER_POWER_INLINE)
/**
Expand Down Expand Up @@ -3378,6 +3375,25 @@
//#define JOYSTICK_DEBUG
#endif

/**
* Mechanical Gantry Calibration
* Modern replacement for the Prusa TMC_Z_CALIBRATION.
* Adds capability to work with any adjustable current drivers.
* Implemented as G34 because M915 is deprecated.
*/
//#define MECHANICAL_GANTRY_CALIBRATION
#if ENABLED(MECHANICAL_GANTRY_CALIBRATION)
#define GANTRY_CALIBRATION_CURRENT 600 // Default calibration current in ma
#define GANTRY_CALIBRATION_EXTRA_HEIGHT 15 // Extra distance in mm past Z_###_POS to move
#define GANTRY_CALIBRATION_FEEDRATE 500 // Feedrate for correction move
//#define GANTRY_CALIBRATION_TO_MIN // Enable to calibrate Z in the MIN direction

//#define GANTRY_CALIBRATION_SAFE_POSITION { X_CENTER, Y_CENTER } // Safe position for nozzle
//#define GANTRY_CALIBRATION_XY_PARK_FEEDRATE 3000 // XY Park Feedrate - MMM
//#define GANTRY_CALIBRATION_COMMANDS_PRE ""
#define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position
#endif

/**
* MAX7219 Debug Matrix
*
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va
}

#if ENABLED(LIGHTWEIGHT_UI)
#include "../../../lcd/ultralcd.h"
#include "../../../lcd/marlinui.h"
#include "../../shared/HAL_ST7920.h"

#define ST7920_CS_PIN LCD_PINS_RS
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ void Stepper::digipot_init() {
NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals)
}

void Stepper::digipot_current(const uint8_t driver, const int16_t current) {
void Stepper::set_digipot_current(const uint8_t driver, const int16_t current) {

if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION)

#ifndef I2C_ADDRESS
#define I2C_ADDRESS(A) (A)
#define I2C_ADDRESS(A) uint8_t(A)
#endif

// Needed for AVR sprintf_P PROGMEM extension
Expand Down
7 changes: 0 additions & 7 deletions Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,3 @@
#if HAS_FSMC_TFT
#error "Sorry! FSMC TFT displays are not current available for HAL/LPC1768."
#endif

// This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046'
#if ENABLED(TOUCH_SCREEN) && !HAS_GRAPHICAL_TFT
#undef TOUCH_SCREEN
#undef TOUCH_SCREEN_CALIBRATION
#define HAS_TOUCH_XPT2046 1
#endif
4 changes: 2 additions & 2 deletions Marlin/src/HAL/LPC1768/inc/SanityCheck.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are in
//#endif

#if MB(RAMPS_14_RE_ARM_EFB, RAMPS_14_RE_ARM_EEB, RAMPS_14_RE_ARM_EFF, RAMPS_14_RE_ARM_EEF, RAMPS_14_RE_ARM_SF)
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI)
#if IS_RRD_FG_SC && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI)
#error "Re-ARM with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER and TMC2130 requires TMC_USE_SW_SPI."
#endif
#endif
Expand Down Expand Up @@ -191,7 +191,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
//
// Flag any i2c pin conflicts
//
#if ANY(HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
#if ANY(HAS_MOTOR_CURRENT_I2C, HAS_MOTOR_CURRENT_DAC, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
#define USEDI2CDEV_M 1 // <Arduino>/Wire.cpp

#if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1)
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/LPC1768/tft/tft_spi.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#define DATASIZE_8BIT SSP_DATABIT_8
#define DATASIZE_16BIT SSP_DATABIT_16
#define TFT_IO TFT_SPI
#define TFT_IO_DRIVER TFT_SPI

#define DMA_MINC_ENABLE 1
#define DMA_MINC_DISABLE 0
Expand Down
3 changes: 2 additions & 1 deletion Marlin/src/HAL/SAMD51/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@

// MYSERIAL0 required before MarlinSerial includes!

#define _MSERIAL(X) Serial##X
#define __MSERIAL(X) Serial##X
#define _MSERIAL(X) __MSERIAL(X)
#define MSERIAL(X) _MSERIAL(INCREMENT(X))

#if SERIAL_PORT == -1
Expand Down
10 changes: 5 additions & 5 deletions Marlin/src/HAL/STM32/fastio.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,15 +51,15 @@ void FastIO_init(); // Must be called before using fast io macros

#if defined(STM32F0xx) || defined(STM32F1xx) || defined(STM32F3xx) || defined(STM32L0xx) || defined(STM32L4xx)
#define _WRITE(IO, V) do { \
if (V) FastIOPortMap[STM_PORT(digitalPin[IO])]->BSRR = _BV32(STM_PIN(digitalPin[IO])) ; \
else FastIOPortMap[STM_PORT(digitalPin[IO])]->BRR = _BV32(STM_PIN(digitalPin[IO])) ; \
if (V) FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->BSRR = _BV32(STM_PIN(digitalPinToPinName(IO))) ; \
else FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->BRR = _BV32(STM_PIN(digitalPinToPinName(IO))) ; \
}while(0)
#else
#define _WRITE(IO, V) (FastIOPortMap[STM_PORT(digitalPin[IO])]->BSRR = _BV32(STM_PIN(digitalPin[IO]) + ((V) ? 0 : 16)))
#define _WRITE(IO, V) (FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->BSRR = _BV32(STM_PIN(digitalPinToPinName(IO)) + ((V) ? 0 : 16)))
#endif

#define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPin[IO])]->IDR, _BV32(STM_PIN(digitalPin[IO]))))
#define _TOGGLE(IO) (FastIOPortMap[STM_PORT(digitalPin[IO])]->ODR ^= _BV32(STM_PIN(digitalPin[IO])))
#define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->IDR, _BV32(STM_PIN(digitalPinToPinName(IO)))))
#define _TOGGLE(IO) (FastIOPortMap[STM_PORT(digitalPinToPinName(IO))]->ODR ^= _BV32(STM_PIN(digitalPinToPinName(IO))))

#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
Expand Down
10 changes: 4 additions & 6 deletions Marlin/src/HAL/STM32/pinsDebug_STM32duino.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@
* It contains:
* - name of the signal
* - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
* EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as an
* index into digitalPin[] to get the Port_pin number
* EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the
* argument to digitalPinToPinName(IO) to get the Port_pin number
* - if it is a digital or analog signal. PWMs are considered digital here.
*
* pin_xref is a structure generated by this header file. It is generated by the
Expand All @@ -68,8 +68,6 @@
* signal. The Arduino pin number is listed by the M43 I command.
*/

extern const PinName digitalPin[]; // provided by the platform

////////////////////////////////////////////////////////
//
// make a list of the Arduino pin numbers in the Port/Pin order
Expand Down Expand Up @@ -137,7 +135,7 @@ const XrefInfo pin_xref[] PROGMEM = {

uint8_t get_pin_mode(const pin_t Ard_num) {
uint32_t mode_all = 0;
const PinName dp = digitalPin[Ard_num];
const PinName dp = digitalPinToPinName(Ard_num);
switch (PORT_ALPHA(dp)) {
case 'A' : mode_all = GPIOA->MODER; break;
case 'B' : mode_all = GPIOB->MODER; break;
Expand Down Expand Up @@ -218,7 +216,7 @@ bool pwm_status(const pin_t Ard_num) {
void pwm_details(const pin_t Ard_num) {
if (pwm_status(Ard_num)) {
uint32_t alt_all = 0;
const PinName dp = digitalPin[Ard_num];
const PinName dp = digitalPinToPinName(Ard_num);
pin_t pin_number = uint8_t(PIN_NUM(dp));
const bool over_7 = pin_number >= 8;
const uint8_t ind = over_7 ? 1 : 0;
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/STM32/tft/tft_fsmc.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#define DATASIZE_8BIT SPI_DATASIZE_8BIT
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
#define TFT_IO TFT_FSMC
#define TFT_IO_DRIVER TFT_FSMC

#ifdef STM32F1xx
#define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN)
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/STM32/tft/tft_spi.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#define DATASIZE_8BIT SPI_DATASIZE_8BIT
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
#define TFT_IO TFT_SPI
#define TFT_IO_DRIVER TFT_SPI

class TFT_SPI {
private:
Expand Down
Loading

0 comments on commit 81a8ec6

Please sign in to comment.