Skip to content

Commit

Permalink
Merge branch '2.0.x' of https://github.com/MarlinFirmware/Marlin into…
Browse files Browse the repository at this point in the history
… K8800-2.0.x

* '2.0.x' of https://github.com/MarlinFirmware/Marlin: (46 commits)
  Simple bool in soft_endstops_t
  Add loose soft endstop state, apply to UBL fine-tune (MarlinFirmware#19681)
  Add D100 Watchdog Test (MarlinFirmware#19697)
  Allow MAX31865 resistance values configuration (MarlinFirmware#19695)
  Add REPORT_TRAMMING_MM option (MarlinFirmware#19682)
  Fix motion compile w/out probe-oriented settings (MarlinFirmware#19684)
  Fix I2C_ADDRESS sign warning (MarlinFirmware#19685)
  Fix various errors, warnings in example config builds (MarlinFirmware#19686)
  Fix at90usb1286 build (MarlinFirmware#19687)
  Digipots refactor / cleanup (MarlinFirmware#19690)
  Save PLR on resume from pause (MarlinFirmware#19676)
  Restore correct STM32 port-bits code (MarlinFirmware#19678)
  Fixes for TFTGLCD Panel, FastIO (MarlinFirmware#19614)
  [cron] Bump distribution date (2020-10-13)
  Fix UTF8 handling for Color UI (MarlinFirmware#19708)
  Move @section temperature
  Fix UTF8 handling for Color UI (MarlinFirmware#19708)
  Implement wait_for_user for Color UI (MarlinFirmware#19694)
  Option to prevent (extra) Watchdog init on STM32 (MarlinFirmware#19693)
  Fix screen click reading too often (MarlinFirmware#19696)
  ...
  • Loading branch information
Susis Strolch committed Oct 14, 2020
2 parents 3731431 + e99ddb2 commit 1550bed
Show file tree
Hide file tree
Showing 133 changed files with 2,000 additions and 2,210 deletions.
80 changes: 45 additions & 35 deletions Marlin/Configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -477,6 +477,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 @@ -2504,43 +2510,47 @@
//=============================== Graphical TFTs ==============================
//=============================================================================

//
// TFT display with optional touch screen
// Color Marlin UI with standard menu system
//
//#define TFT_320x240
//#define TFT_320x240_SPI
//#define TFT_480x320
//#define TFT_480x320_SPI

//
// 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
//
//#define TFT_DRIVER AUTO

//
// SPI display (MKS Robin Nano V2.0, MKS Gen L V2.0)
// Upscaled 128x64 Marlin UI
//
//#define SPI_GRAPHICAL_TFT
/**
* TFT Type - Select your Display type
*
* Available options are:
* MKS_TS35_V2_0,
* MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32, MKS_ROBIN_TFT35,
* MKS_ROBIN_TFT43, MKS_ROBIN_TFT_V1_1R
* TFT_TRONXY_X5SA, ANYCUBIC_TFT35, LONGER_LK_TFT28
* TFT_GENERIC
*
* For TFT_GENERIC, you need to configure these 3 options:
* Driver: TFT_DRIVER
* Current Drivers are: AUTO, ST7735, ST7789, ST7796, R61505, ILI9328, ILI9341, ILI9488
* Resolution: TFT_WIDTH and TFT_HEIGHT
* Interface: TFT_INTERFACE_FSMC or TFT_INTERFACE_SPI
*/
//#define TFT_GENERIC

//
// FSMC display (MKS Robin, Alfawise U20, JGAurora A5S, REXYZ A1, etc.)
// Upscaled 128x64 Marlin UI
//
//#define FSMC_GRAPHICAL_TFT
/**
* 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 LVGL UI
//
// 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.
//
//#define TFT_LVGL_UI_FSMC // Robin nano v1.2 uses FSMC
//#define TFT_LVGL_UI_SPI // Robin nano v2.0 uses SPI
/**
* 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

//=============================================================================
//============================ Other Controllers ============================
Expand Down
30 changes: 23 additions & 7 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -840,11 +840,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 @@ -1613,10 +1611,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 @@ -3429,6 +3426,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
4 changes: 2 additions & 2 deletions Marlin/src/HAL/AVR/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "watchdog.h"
#include "math.h"

#ifdef USBCON
#ifdef IS_AT90USB
#include <HardwareSerial.h>
#else
#define HardwareSerial_h // Hack to prevent HardwareSerial.h header inclusion
Expand Down Expand Up @@ -81,7 +81,7 @@ typedef int8_t pin_t;
//extern uint8_t MCUSR;

// Serial ports
#ifdef USBCON
#ifdef IS_AT90USB
#define MYSERIAL0 TERN(BLUETOOTH, bluetoothSerial, Serial)
#else
#if !WITHIN(SERIAL_PORT, -1, 3)
Expand Down
6 changes: 3 additions & 3 deletions Marlin/src/HAL/AVR/MarlinSerial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#include "../../inc/MarlinConfig.h"

#if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
#if !IS_AT90USB && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))

#include "MarlinSerial.h"
#include "../../MarlinCore.h"
Expand Down Expand Up @@ -792,10 +792,10 @@ MarlinSerial<MarlinSerialCfg<SERIAL_PORT>> customizedSerial1;

#endif

#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
#endif // !IS_AT90USB && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)

// For AT90USB targets use the UART for BT interfacing
#if defined(USBCON) && ENABLED(BLUETOOTH)
#if BOTH(IS_AT90USB, BLUETOOTH)
HardwareSerial bluetoothSerial;
#endif

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/AVR/MarlinSerial.h
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,6 @@
#endif

// Use the UART for Bluetooth in AT90USB configurations
#if defined(USBCON) && ENABLED(BLUETOOTH)
#if BOTH(IS_AT90USB, BLUETOOTH)
extern HardwareSerial bluetoothSerial;
#endif
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
2 changes: 1 addition & 1 deletion Marlin/src/HAL/LPC1768/inc/SanityCheck.h
Original file line number Diff line number Diff line change
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
8 changes: 4 additions & 4 deletions Marlin/src/HAL/STM32/fastio.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ void FastIO_init(); // Must be called before using fast io macros

#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) //!< Output Push Pull Mode & GPIO_NOPULL
#define _SET_OUTPUT_OD(IO) pinMode(IO, OUTPUT_OPEN_DRAIN)

#define WRITE(IO,V) _WRITE(IO,V)
Expand All @@ -73,9 +73,9 @@ void FastIO_init(); // Must be called before using fast io macros
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0)

#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) //!< Input Floating Mode
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) //!< Input with Pull-up activation
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) //!< Input with Pull-down activation
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) _SET_MODE(IO, PWM)

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
6 changes: 5 additions & 1 deletion Marlin/src/HAL/STM32/watchdog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,11 @@
#include "watchdog.h"
#include <IWatchdog.h>

void watchdog_init() { IWatchdog.begin(4000000); } // 4 sec timeout
void watchdog_init() {
#if DISABLED(DISABLE_WATCHDOG_INIT)
IWatchdog.begin(4000000); // 4 sec timeout
#endif
}

void HAL_watchdog_refresh() {
IWatchdog.reload();
Expand Down
3 changes: 1 addition & 2 deletions Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)

#include "../HAL.h"
#include <U8glib.h>

#undef SPI_SPEED
Expand Down Expand Up @@ -161,5 +160,5 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
return 1;
}

#endif // HAS_MARLINUI_U8GLIB
#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI
#endif // STM32F1
7 changes: 0 additions & 7 deletions Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,3 @@
//#warning "SD_CHECK_AND_RETRY isn't needed with USE_USB_COMPOSITE."
#undef SD_CHECK_AND_RETRY
#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
13 changes: 0 additions & 13 deletions Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,25 +89,12 @@ void TFT_FSMC::Init() {
uint8_t cs = FSMC_CS_PIN, rs = FSMC_RS_PIN;
uint32_t controllerAddress;

#if PIN_EXISTS(TFT_BACKLIGHT)
OUT_WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT));
#endif

#if ENABLED(LCD_USE_DMA_FSMC)
dma_init(FSMC_DMA_DEV);
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
dma_set_priority(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, DMA_PRIORITY_MEDIUM);
#endif

#if PIN_EXISTS(TFT_RESET)
OUT_WRITE(TFT_RESET_PIN, HIGH);
delay(100);
#endif

#if PIN_EXISTS(TFT_BACKLIGHT)
OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
#endif

struct fsmc_nor_psram_reg_map* fsmcPsramRegion;

if (fsmcInit) return;
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/STM32F1/tft/tft_fsmc.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@

#define DATASIZE_8BIT DMA_SIZE_8BITS
#define DATASIZE_16BIT DMA_SIZE_16BITS
#define TFT_IO TFT_FSMC
#define TFT_IO_DRIVER TFT_FSMC

typedef struct {
__IO uint16_t REG;
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/STM32F1/tft/tft_spi.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#define DATASIZE_8BIT DATA_SIZE_8BIT
#define DATASIZE_16BIT DATA_SIZE_16BIT
#define TFT_IO TFT_SPI
#define TFT_IO_DRIVER TFT_SPI

#define DMA_MINC_ENABLE 1
#define DMA_MINC_DISABLE 0
Expand Down
4 changes: 3 additions & 1 deletion Marlin/src/HAL/STM32F1/watchdog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,9 @@ void watchdogSetup() {
* @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0)
*/
void watchdog_init() {
//iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
#if DISABLED(DISABLE_WATCHDOG_INIT)
iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
#endif
}

#endif // USE_WATCHDOG
Expand Down
Loading

0 comments on commit 1550bed

Please sign in to comment.