Merge tag '2.0.7.2' into master

This commit is contained in:
2020-11-17 18:53:19 -06:00
367 changed files with 30156 additions and 10192 deletions

View File

@ -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
@ -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)
@ -120,6 +120,8 @@ void HAL_init();
inline void HAL_clear_reset_source() { MCUSR = 0; }
inline uint8_t HAL_get_reset_source() { return MCUSR; }
inline void HAL_reboot() {} // reboot the board or restart the bootloader
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
extern "C" {

View File

@ -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"
@ -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

View File

@ -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

View File

@ -185,8 +185,8 @@ void set_pwm_frequency(const pin_t pin, int f_desired) {
res_temp_phase_correct = rtf / 2;
}
LIMIT(res_temp_fast, 1u, size);
LIMIT(res_temp_phase_correct, 1u, size);
LIMIT(res_temp_fast, 1U, size);
LIMIT(res_temp_phase_correct, 1U, size);
// Calculate frequencies of test prescaler and resolution values
const int f_temp_fast = (F_CPU) / (prescaler[i] * (1 + res_temp_fast)),
f_temp_phase_correct = (F_CPU) / (2 * prescaler[i] * res_temp_phase_correct),

View File

@ -19,9 +19,7 @@
*/
/**
* Description: HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
* HAL for Arduino Due and compatible (SAM3X8E)
*/
#ifdef ARDUINO_ARCH_SAM

View File

@ -22,9 +22,7 @@
#pragma once
/**
* Description: HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
* HAL for Arduino Due and compatible (SAM3X8E)
*/
#define CPU_32_BIT
@ -107,13 +105,15 @@ void sei(); // Enable interrupts
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
inline void HAL_reboot() {} // reboot the board or restart the bootloader
//
// ADC
//
extern uint16_t HAL_adc_result; // result of last ADC conversion
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define HAL_ANALOG_SELECT(ch)

View File

@ -30,7 +30,7 @@
*/
/**
* Description: HAL for Arduino Due and compatible (SAM3X8E)
* HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
*/

View File

@ -60,7 +60,7 @@
#define EEPROMSize 4096
#define PagesPerGroup 128
#define GroupCount 2
#define PageSize 256u
#define PageSize 256U
/* Flash storage */
typedef struct FLASH_SECTOR {

View File

@ -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

View File

@ -21,9 +21,7 @@
*/
/**
* Description: HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
* HAL Timers for Arduino Due and compatible (SAM3X8E)
*/
#ifdef ARDUINO_ARCH_SAM

View File

@ -21,9 +21,7 @@
#pragma once
/**
* HAL for Arduino Due and compatible (SAM3X8E)
*
* For ARDUINO_ARCH_SAM
* HAL Timers for Arduino Due and compatible (SAM3X8E)
*/
#include <stdint.h>

View File

@ -14,5 +14,5 @@ if current_OS == 'Windows':
# Use bossac.exe on Windows
env.Replace(
UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot"
UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE"
)

View File

@ -609,37 +609,37 @@ typedef struct
# define clz(u) ((u) ? __CLZ(u) : 32)
#else
# define clz(u) (((u) == 0) ? 32 : \
((u) & (1ul << 31)) ? 0 : \
((u) & (1ul << 30)) ? 1 : \
((u) & (1ul << 29)) ? 2 : \
((u) & (1ul << 28)) ? 3 : \
((u) & (1ul << 27)) ? 4 : \
((u) & (1ul << 26)) ? 5 : \
((u) & (1ul << 25)) ? 6 : \
((u) & (1ul << 24)) ? 7 : \
((u) & (1ul << 23)) ? 8 : \
((u) & (1ul << 22)) ? 9 : \
((u) & (1ul << 21)) ? 10 : \
((u) & (1ul << 20)) ? 11 : \
((u) & (1ul << 19)) ? 12 : \
((u) & (1ul << 18)) ? 13 : \
((u) & (1ul << 17)) ? 14 : \
((u) & (1ul << 16)) ? 15 : \
((u) & (1ul << 15)) ? 16 : \
((u) & (1ul << 14)) ? 17 : \
((u) & (1ul << 13)) ? 18 : \
((u) & (1ul << 12)) ? 19 : \
((u) & (1ul << 11)) ? 20 : \
((u) & (1ul << 10)) ? 21 : \
((u) & (1ul << 9)) ? 22 : \
((u) & (1ul << 8)) ? 23 : \
((u) & (1ul << 7)) ? 24 : \
((u) & (1ul << 6)) ? 25 : \
((u) & (1ul << 5)) ? 26 : \
((u) & (1ul << 4)) ? 27 : \
((u) & (1ul << 3)) ? 28 : \
((u) & (1ul << 2)) ? 29 : \
((u) & (1ul << 1)) ? 30 : \
((u) & (1UL << 31)) ? 0 : \
((u) & (1UL << 30)) ? 1 : \
((u) & (1UL << 29)) ? 2 : \
((u) & (1UL << 28)) ? 3 : \
((u) & (1UL << 27)) ? 4 : \
((u) & (1UL << 26)) ? 5 : \
((u) & (1UL << 25)) ? 6 : \
((u) & (1UL << 24)) ? 7 : \
((u) & (1UL << 23)) ? 8 : \
((u) & (1UL << 22)) ? 9 : \
((u) & (1UL << 21)) ? 10 : \
((u) & (1UL << 20)) ? 11 : \
((u) & (1UL << 19)) ? 12 : \
((u) & (1UL << 18)) ? 13 : \
((u) & (1UL << 17)) ? 14 : \
((u) & (1UL << 16)) ? 15 : \
((u) & (1UL << 15)) ? 16 : \
((u) & (1UL << 14)) ? 17 : \
((u) & (1UL << 13)) ? 18 : \
((u) & (1UL << 12)) ? 19 : \
((u) & (1UL << 11)) ? 20 : \
((u) & (1UL << 10)) ? 21 : \
((u) & (1UL << 9)) ? 22 : \
((u) & (1UL << 8)) ? 23 : \
((u) & (1UL << 7)) ? 24 : \
((u) & (1UL << 6)) ? 25 : \
((u) & (1UL << 5)) ? 26 : \
((u) & (1UL << 4)) ? 27 : \
((u) & (1UL << 3)) ? 28 : \
((u) & (1UL << 2)) ? 29 : \
((u) & (1UL << 1)) ? 30 : \
31)
#endif
#endif
@ -654,38 +654,38 @@ typedef struct
#if (defined __GNUC__) || (defined __CC_ARM)
# define ctz(u) ((u) ? __builtin_ctz(u) : 32)
#else
# define ctz(u) ((u) & (1ul << 0) ? 0 : \
(u) & (1ul << 1) ? 1 : \
(u) & (1ul << 2) ? 2 : \
(u) & (1ul << 3) ? 3 : \
(u) & (1ul << 4) ? 4 : \
(u) & (1ul << 5) ? 5 : \
(u) & (1ul << 6) ? 6 : \
(u) & (1ul << 7) ? 7 : \
(u) & (1ul << 8) ? 8 : \
(u) & (1ul << 9) ? 9 : \
(u) & (1ul << 10) ? 10 : \
(u) & (1ul << 11) ? 11 : \
(u) & (1ul << 12) ? 12 : \
(u) & (1ul << 13) ? 13 : \
(u) & (1ul << 14) ? 14 : \
(u) & (1ul << 15) ? 15 : \
(u) & (1ul << 16) ? 16 : \
(u) & (1ul << 17) ? 17 : \
(u) & (1ul << 18) ? 18 : \
(u) & (1ul << 19) ? 19 : \
(u) & (1ul << 20) ? 20 : \
(u) & (1ul << 21) ? 21 : \
(u) & (1ul << 22) ? 22 : \
(u) & (1ul << 23) ? 23 : \
(u) & (1ul << 24) ? 24 : \
(u) & (1ul << 25) ? 25 : \
(u) & (1ul << 26) ? 26 : \
(u) & (1ul << 27) ? 27 : \
(u) & (1ul << 28) ? 28 : \
(u) & (1ul << 29) ? 29 : \
(u) & (1ul << 30) ? 30 : \
(u) & (1ul << 31) ? 31 : \
# define ctz(u) ((u) & (1UL << 0) ? 0 : \
(u) & (1UL << 1) ? 1 : \
(u) & (1UL << 2) ? 2 : \
(u) & (1UL << 3) ? 3 : \
(u) & (1UL << 4) ? 4 : \
(u) & (1UL << 5) ? 5 : \
(u) & (1UL << 6) ? 6 : \
(u) & (1UL << 7) ? 7 : \
(u) & (1UL << 8) ? 8 : \
(u) & (1UL << 9) ? 9 : \
(u) & (1UL << 10) ? 10 : \
(u) & (1UL << 11) ? 11 : \
(u) & (1UL << 12) ? 12 : \
(u) & (1UL << 13) ? 13 : \
(u) & (1UL << 14) ? 14 : \
(u) & (1UL << 15) ? 15 : \
(u) & (1UL << 16) ? 16 : \
(u) & (1UL << 17) ? 17 : \
(u) & (1UL << 18) ? 18 : \
(u) & (1UL << 19) ? 19 : \
(u) & (1UL << 20) ? 20 : \
(u) & (1UL << 21) ? 21 : \
(u) & (1UL << 22) ? 22 : \
(u) & (1UL << 23) ? 23 : \
(u) & (1UL << 24) ? 24 : \
(u) & (1UL << 25) ? 25 : \
(u) & (1UL << 26) ? 26 : \
(u) & (1UL << 27) ? 27 : \
(u) & (1UL << 28) ? 28 : \
(u) & (1UL << 29) ? 29 : \
(u) & (1UL << 30) ? 30 : \
(u) & (1UL << 31) ? 31 : \
32)
#endif
#endif

View File

@ -20,7 +20,7 @@
#pragma once
/**
* Description: HAL for Espressif ESP32 WiFi
* HAL for Espressif ESP32 WiFi
*/
#define CPU_32_BIT
@ -96,6 +96,8 @@ void HAL_clear_reset_source();
// reset reason
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
void _delay_ms(int delay);
#pragma GCC diagnostic push
@ -155,14 +157,14 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) {
if (stop >= start) {
// no overflow, so only loop while in between start and stop:
// 0x00000000 -----------------start****stop-- 0xffffffff
// 0x00000000 -----------------start****stop-- 0xFFFFFFFF
while (ccount >= start && ccount < stop) {
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
}
}
else {
// stop did overflow, so only loop while outside of stop and start:
// 0x00000000 **stop-------------------start** 0xffffffff
// 0x00000000 **stop-------------------start** 0xFFFFFFFF
while (ccount >= start || ccount < stop) {
__asm__ __volatile__ ( "rsr %0, ccount" : "=a" (ccount) );
}

View File

@ -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

View File

@ -101,6 +101,8 @@ uint16_t HAL_adc_get_result();
inline void HAL_clear_reset_source(void) {}
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
inline void HAL_reboot() {} // reboot the board or restart the bootloader
/* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x);

View File

@ -200,6 +200,8 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255,
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);
inline void HAL_reboot() {} // reboot the board or restart the bootloader
// Add strcmp_P if missing
#ifndef strcmp_P
#define strcmp_P(a, b) strcmp((a), (b))

View File

@ -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

View File

@ -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)

View File

@ -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

View File

@ -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
@ -88,6 +89,8 @@ typedef int8_t pin_t;
void HAL_clear_reset_source(); // clear reset reason
uint8_t HAL_get_reset_source(); // get reset reason
inline void HAL_reboot() {} // reboot the board or restart the bootloader
//
// ADC
//

View File

@ -26,7 +26,7 @@
#include "QSPIFlash.h"
#define INVALID_ADDR 0xffffffff
#define INVALID_ADDR 0xFFFFFFFF
#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1))
#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1))

View File

@ -63,7 +63,7 @@ uint16_t HAL_adc_result;
void HAL_init() {
FastIO_init();
#if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT)
#if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
#endif
@ -122,9 +122,14 @@ extern "C" {
// TODO: Make sure this doesn't cause any delay
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
// Reset the system (to initiate a firmware flash)
void flashFirmware(const int16_t) { NVIC_SystemReset(); }
// Maple Compatibility
systickCallback_t systick_user_callback;
void systick_attach_callback(systickCallback_t cb) { systick_user_callback = cb; }
void HAL_SYSTICK_Callback() { if (systick_user_callback) systick_user_callback(); }
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -134,6 +134,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
void _delay_ms(const int delay);
extern "C" char* _sbrk(int incr);
@ -177,3 +179,8 @@ uint16_t HAL_adc_get_result();
#define PLATFORM_M997_SUPPORT
void flashFirmware(const int16_t);
// Maple Compatibility
typedef void (*systickCallback_t)(void);
void systick_attach_callback(systickCallback_t cb);
void HAL_SYSTICK_Callback();

View File

@ -132,11 +132,9 @@ static SPISettings spiConfig;
* @details Only configures SS pin since stm32duino creates and initialize the SPI object
*/
void spiBegin() {
#if !PIN_EXISTS(SS)
#error "SS_PIN not defined!"
#if PIN_EXISTS(SS)
OUT_WRITE(SS_PIN, HIGH);
#endif
OUT_WRITE(SS_PIN, HIGH);
}
// Configure SPI for specified SPI speed
@ -173,9 +171,7 @@ static SPISettings spiConfig;
* @details
*/
uint8_t spiRec() {
SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction();
return returnByte;
}
@ -191,9 +187,7 @@ static SPISettings spiConfig;
void spiRead(uint8_t* buf, uint16_t nbyte) {
if (nbyte == 0) return;
memset(buf, 0xFF, nbyte);
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
}
/**
@ -204,9 +198,7 @@ static SPISettings spiConfig;
* @details
*/
void spiSend(uint8_t b) {
SPI.beginTransaction(spiConfig);
SPI.transfer(b);
SPI.endTransaction();
}
/**
@ -219,10 +211,8 @@ static SPISettings spiConfig;
*/
void spiSendBlock(uint8_t token, const uint8_t* buf) {
uint8_t rxBuf[512];
SPI.beginTransaction(spiConfig);
SPI.transfer(token);
SPI.transfer((uint8_t*)buf, &rxBuf, 512);
SPI.endTransaction();
}
#endif // SOFTWARE_SPI

View File

@ -51,19 +51,19 @@ 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)
#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)
@ -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)

View File

@ -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
@ -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
@ -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;
@ -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;

View File

@ -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)

View File

@ -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:

View File

@ -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();

View File

@ -97,6 +97,9 @@ const uint8_t adc_pins[] = {
#if HAS_TEMP_ADC_0
TEMP_0_PIN,
#endif
#if HAS_TEMP_ADC_PROBE
TEMP_PROBE_PIN,
#endif
#if HAS_HEATED_BED
TEMP_BED_PIN,
#endif
@ -151,6 +154,9 @@ enum TempPinIndex : char {
#if HAS_TEMP_ADC_0
TEMP_0,
#endif
#if HAS_TEMP_ADC_PROBE
TEMP_PROBE,
#endif
#if HAS_HEATED_BED
TEMP_BED,
#endif
@ -341,6 +347,9 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
#if HAS_TEMP_ADC_0
case TEMP_0_PIN: pin_index = TEMP_0; break;
#endif
#if HAS_TEMP_ADC_PROBE
case TEMP_PROBE_PIN: pin_index = TEMP_PROBE; break;
#endif
#if HAS_HEATED_BED
case TEMP_BED_PIN: pin_index = TEMP_BED; break;
#endif

View File

@ -185,6 +185,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
void _delay_ms(const int delay);
#pragma GCC diagnostic push

View File

@ -24,9 +24,6 @@
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (c) 2009 by William Greiman
*/
/**
* Adapted to the STM32F1 HAL
*/
@ -113,7 +110,7 @@ void spiInit(uint8_t spiRate) {
* @details
*/
uint8_t spiRec() {
uint8_t returnByte = SPI.transfer(ff);
uint8_t returnByte = SPI.transfer(0xFF);
return returnByte;
}
@ -157,7 +154,7 @@ void spiSendBlock(uint8_t token, const uint8_t* buf) {
#if ENABLED(SPI_EEPROM)
// Read single byte from specified SPI channel
uint8_t spiRec(uint32_t chan) { return SPI.transfer(ff); }
uint8_t spiRec(uint32_t chan) { return SPI.transfer(0xFF); }
// Write single byte to specified SPI channel
void spiSend(uint32_t chan, byte b) { SPI.send(b); }

View File

@ -22,7 +22,6 @@
#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
#include "../HAL.h"
#include <U8glib.h>
#undef SPI_SPEED
@ -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

View File

@ -25,6 +25,8 @@
* with simple implementations supplied by Marlin.
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
@ -79,3 +81,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
}
#endif // IIC_BL24CXX_EEPROM
#endif // __STM32F1__

View File

@ -25,6 +25,8 @@
* Enable USE_SHARED_EEPROM if not supplied by the framework.
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
@ -49,3 +51,4 @@ uint8_t eeprom_read_byte(uint8_t *pos) {
}
#endif // IIC_BL24CXX_EEPROM
#endif // __STM32F1__

View File

@ -17,17 +17,17 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL PersistentStore for STM32F1
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if USE_WIRED_EEPROM
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
#include "../shared/eeprom_if.h"
#include "../shared/eeprom_api.h"

View File

@ -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

View File

@ -13,7 +13,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef USE_USB_COMPOSITE
#if defined(__STM32F1__) && defined(USE_USB_COMPOSITE)
#include "msc_sd.h"
#include "SPI.h"
@ -77,4 +77,4 @@ void MSC_SD_init() {
#endif
}
#endif // USE_USB_COMPOSITE
#endif // __STM32F1__ && USE_USB_COMPOSITE

View File

@ -11,6 +11,8 @@
* Redistributions of source code must retain the above copyright notice.
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if SD_CONNECTION_IS(ONBOARD)
@ -553,3 +555,4 @@ DRESULT disk_read (
#endif // _DISKIO_IOCTL
#endif // SD_CONNECTION_IS(ONBOARD)
#endif // __STM32F1__

View File

@ -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;

View File

@ -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;

View File

@ -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

View File

@ -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

View File

@ -142,6 +142,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
void _delay_ms(const int delay);
/*

View File

@ -45,8 +45,8 @@
#define DEFAULT_MICROSTEPPING_VALUE 32
//TMC26X register definitions
#define DRIVER_CONTROL_REGISTER 0x0ul
#define CHOPPER_CONFIG_REGISTER 0x80000ul
#define DRIVER_CONTROL_REGISTER 0x0UL
#define CHOPPER_CONFIG_REGISTER 0x80000UL
#define COOL_STEP_REGISTER 0xA0000ul
#define STALL_GUARD2_LOAD_MEASURE_REGISTER 0xC0000ul
#define DRIVER_CONFIG_REGISTER 0xE0000ul
@ -55,58 +55,58 @@
//definitions for the driver control register
#define MICROSTEPPING_PATTERN 0xFul
#define STEP_INTERPOLATION 0x200ul
#define DOUBLE_EDGE_STEP 0x100ul
#define VSENSE 0x40ul
#define READ_MICROSTEP_POSTION 0x0ul
#define READ_STALL_GUARD_READING 0x10ul
#define READ_STALL_GUARD_AND_COOL_STEP 0x20ul
#define READ_SELECTION_PATTERN 0x30ul
#define STEP_INTERPOLATION 0x200UL
#define DOUBLE_EDGE_STEP 0x100UL
#define VSENSE 0x40UL
#define READ_MICROSTEP_POSTION 0x0UL
#define READ_STALL_GUARD_READING 0x10UL
#define READ_STALL_GUARD_AND_COOL_STEP 0x20UL
#define READ_SELECTION_PATTERN 0x30UL
//definitions for the chopper config register
#define CHOPPER_MODE_STANDARD 0x0ul
#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000ul
#define CHOPPER_MODE_STANDARD 0x0UL
#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000UL
#define T_OFF_PATTERN 0xFul
#define RANDOM_TOFF_TIME 0x2000ul
#define BLANK_TIMING_PATTERN 0x18000ul
#define RANDOM_TOFF_TIME 0x2000UL
#define BLANK_TIMING_PATTERN 0x18000UL
#define BLANK_TIMING_SHIFT 15
#define HYSTERESIS_DECREMENT_PATTERN 0x1800ul
#define HYSTERESIS_DECREMENT_PATTERN 0x1800UL
#define HYSTERESIS_DECREMENT_SHIFT 11
#define HYSTERESIS_LOW_VALUE_PATTERN 0x780ul
#define HYSTERESIS_LOW_VALUE_PATTERN 0x780UL
#define HYSTERESIS_LOW_SHIFT 7
#define HYSTERESIS_START_VALUE_PATTERN 0x78ul
#define HYSTERESIS_START_VALUE_PATTERN 0x78UL
#define HYSTERESIS_START_VALUE_SHIFT 4
#define T_OFF_TIMING_PATERN 0xFul
//definitions for cool step register
#define MINIMUM_CURRENT_FOURTH 0x8000ul
#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000ul
#define MINIMUM_CURRENT_FOURTH 0x8000UL
#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000UL
#define SE_MAX_PATTERN 0xF00ul
#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60ul
#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60UL
#define SE_MIN_PATTERN 0xFul
//definitions for StallGuard2 current register
#define STALL_GUARD_FILTER_ENABLED 0x10000ul
#define STALL_GUARD_FILTER_ENABLED 0x10000UL
#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul
#define CURRENT_SCALING_PATTERN 0x1Ful
#define STALL_GUARD_CONFIG_PATTERN 0x17F00ul
#define STALL_GUARD_VALUE_PATTERN 0x7F00ul
//definitions for the input from the TMC2660
#define STATUS_STALL_GUARD_STATUS 0x1ul
#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2ul
#define STATUS_OVER_TEMPERATURE_WARNING 0x4ul
#define STATUS_SHORT_TO_GROUND_A 0x8ul
#define STATUS_SHORT_TO_GROUND_B 0x10ul
#define STATUS_OPEN_LOAD_A 0x20ul
#define STATUS_OPEN_LOAD_B 0x40ul
#define STATUS_STAND_STILL 0x80ul
#define STATUS_STALL_GUARD_STATUS 0x1UL
#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2UL
#define STATUS_OVER_TEMPERATURE_WARNING 0x4UL
#define STATUS_SHORT_TO_GROUND_A 0x8UL
#define STATUS_SHORT_TO_GROUND_B 0x10UL
#define STATUS_OPEN_LOAD_A 0x20UL
#define STATUS_OPEN_LOAD_B 0x40UL
#define STATUS_STAND_STILL 0x80UL
#define READOUT_VALUE_PATTERN 0xFFC00ul
#define CPU_32_BIT
//default values
#define INITIAL_MICROSTEPPING 0x3ul //32th microstepping
#define INITIAL_MICROSTEPPING 0x3UL //32th microstepping
SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN);

View File

@ -20,9 +20,8 @@
*
*/
/**
* Description: HAL for Teensy32 (MK20DX256)
* HAL for Teensy 3.2 (MK20DX256)
*/
#ifdef __MK20DX256__

View File

@ -22,7 +22,7 @@
#pragma once
/**
* Description: HAL for Teensy 3.5 and Teensy 3.6
* HAL for Teensy 3.2 (MK20DX256)
*/
#define CPU_32_BIT
@ -44,8 +44,9 @@
//#undef MOTHERBOARD
//#define MOTHERBOARD BOARD_TEENSY31_32
#ifdef __MK20DX256__
#define IS_32BIT_TEENSY 1
#define IS_32BIT_TEENSY 1
#define IS_TEENSY_31_32 1
#ifndef IS_TEENSY31
#define IS_TEENSY32 1
#endif
@ -64,7 +65,7 @@
typedef int8_t pin_t;
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
@ -92,6 +93,8 @@ void HAL_clear_reset_source();
// Get the reason for the reset
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push

View File

@ -51,5 +51,4 @@ void libServo::move(const int value) {
}
#endif // HAS_SERVOS
#endif // __MK20DX256__

View File

@ -23,8 +23,7 @@
#if USE_WIRED_EEPROM
/**
* PersistentStore for Arduino-style EEPROM interface
* with implementations supplied by the framework.
* HAL PersistentStore for Teensy 3.2 (MK20DX256)
*/
#include "../shared/eeprom_api.h"

View File

@ -21,7 +21,7 @@
*/
/**
* Teensy3.2 __MK20DX256__
* HAL Timers for Teensy 3.2 (MK20DX256)
*/
#ifdef __MK20DX256__

View File

@ -22,8 +22,7 @@
#pragma once
/**
* Description: HAL for
* Teensy3.2 (__MK20DX256__)
* HAL Timers for Teensy 3.2 (MK20DX256)
*/
#include <stdint.h>

View File

@ -21,7 +21,7 @@
*/
/**
* Description: HAL for Teensy35 (MK64FX512)
* HAL for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)

View File

@ -22,7 +22,7 @@
#pragma once
/**
* Description: HAL for Teensy 3.5 and Teensy 3.6
* HAL for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#define CPU_32_BIT
@ -45,13 +45,12 @@
// Defines
// ------------------------
#ifdef __MK64FX512__
#define IS_32BIT_TEENSY 1
#define IS_TEENSY35 1
#endif
#define IS_32BIT_TEENSY 1
#define IS_TEENSY_35_36 1
#ifdef __MK66FX1M0__
#define IS_32BIT_TEENSY 1
#define IS_TEENSY36 1
#else // __MK64FX512__
#define IS_TEENSY35 1
#endif
#define _MSERIAL(X) Serial##X
@ -69,7 +68,7 @@
typedef int8_t pin_t;
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq()
@ -100,6 +99,8 @@ void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
#pragma GCC diagnostic push

View File

@ -19,6 +19,11 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL SPI for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "HAL.h"

View File

@ -19,6 +19,11 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL Servo for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../inc/MarlinConfig.h"
@ -51,5 +56,4 @@ void libServo::move(const int value) {
}
#endif // HAS_SERVOS
#endif // __MK64FX512__ || __MK66FX1M0__

View File

@ -21,6 +21,10 @@
*/
#pragma once
/**
* HAL Servo for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#include <Servo.h>
// Inherit and expand on core Servo library

View File

@ -22,15 +22,14 @@
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
/**
* HAL PersistentStore for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#include "../../inc/MarlinConfig.h"
#if USE_WIRED_EEPROM
/**
* PersistentStore for Arduino-style EEPROM interface
* with implementations supplied by the framework.
*/
#include "../shared/eeprom_api.h"
#include <avr/eeprom.h>

View File

@ -22,7 +22,7 @@
#pragma once
/**
* Endstop Interrupts
* HAL Endstop Interrupts for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*
* Without endstop interrupts the endstop pins must be polled continually in
* the temperature-ISR via endstops.update(), most of the time finding no change.

View File

@ -18,6 +18,10 @@
*/
#pragma once
/**
* HAL Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin

View File

@ -21,6 +21,10 @@
*/
#pragma once
/**
* HAL SPI Pins for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#define SCK_PIN 13
#define MISO_PIN 12
#define MOSI_PIN 11

View File

@ -21,8 +21,7 @@
*/
/**
* Teensy3.5 __MK64FX512__
* Teensy3.6 __MK66FX1M0__
* HAL Timers for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)

View File

@ -21,9 +21,7 @@
#pragma once
/**
* Description: HAL for
* Teensy3.5 (__MK64FX512__)
* Teensy3.6 (__MK66FX1M0__)
* HAL Timers for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
*/
#include <stdint.h>

View File

@ -21,7 +21,7 @@
*/
/**
* Description: HAL for Teensy40 (IMXRT1062)
* HAL for Teensy 4.0 / 4.1 (IMXRT1062)
*/
#ifdef __IMXRT1062__

View File

@ -22,7 +22,7 @@
#pragma once
/**
* Description: HAL for Teensy 4.0 and Teensy 4.1
* HAL for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#define CPU_32_BIT
@ -45,8 +45,9 @@
// Defines
// ------------------------
#ifdef __IMXRT1062__
#define IS_32BIT_TEENSY 1
#define IS_32BIT_TEENSY 1
#define IS_TEENSY_40_41 1
#ifndef IS_TEENSY40
#define IS_TEENSY41 1
#endif
@ -77,7 +78,7 @@
typedef int8_t pin_t;
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq()

View File

@ -19,6 +19,11 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL SPI for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#ifdef __IMXRT1062__
#include "HAL.h"

View File

@ -19,6 +19,11 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL Servo for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#ifdef __IMXRT1062__
#include "../../inc/MarlinConfig.h"
@ -53,5 +58,4 @@ void libServo::detach() {
}
#endif // HAS_SERVOS
#endif // __IMXRT1062__

View File

@ -21,6 +21,10 @@
*/
#pragma once
/**
* HAL Servo for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#include <PWMServo.h>
// Inherit and expand on core Servo library

View File

@ -27,8 +27,7 @@
#if USE_WIRED_EEPROM
/**
* PersistentStore for Arduino-style EEPROM interface
* with implementations supplied by the framework.
* HAL PersistentStore for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#include "../shared/eeprom_api.h"

View File

@ -22,7 +22,7 @@
#pragma once
/**
* Endstop Interrupts
* HAL Endstop Interrupts for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*
* Without endstop interrupts the endstop pins must be polled continually in
* the temperature-ISR via endstops.update(), most of the time finding no change.

View File

@ -23,7 +23,7 @@
#pragma once
/**
* Fast I/O interfaces for Teensy 4
* Fast I/O interfaces for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/

View File

@ -18,6 +18,10 @@
*/
#pragma once
/**
* HAL Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#warning "PINS_DEBUGGING is not fully supported for Teensy 4.0 / 4.1 so 'M43' may cause hangs."
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS

View File

@ -21,6 +21,10 @@
*/
#pragma once
/**
* HAL SPI Pins for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#define SCK_PIN 13
#define MISO_PIN 12
#define MOSI_PIN 11

View File

@ -21,7 +21,7 @@
*/
/**
* Teensy4.0/4.1 (__IMXRT1062__)
* HAL Timers for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#ifdef __IMXRT1062__

View File

@ -21,8 +21,7 @@
#pragma once
/**
* Description: HAL for
* Teensy4.0/4.1 (__IMXRT1062__)
* HAL Timers for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#include <stdint.h>

View File

@ -19,6 +19,11 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
#ifdef __IMXRT1062__
#include "../../inc/MarlinConfig.h"
@ -48,5 +53,4 @@ void HAL_watchdog_refresh() {
}
#endif // USE_WATCHDOG
#endif // __IMXRT1062__

View File

@ -22,7 +22,7 @@
#pragma once
/**
* Watchdog for Teensy4.0/4.1 (__IMXRT1062__)
* HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
*/
void watchdog_init();

View File

@ -85,7 +85,7 @@
#define START_FLASH_ADDR 0x08000000
#define END_FLASH_ADDR 0x08100000
#elif MB(REMRAM_V1)
#elif MB(REMRAM_V1, NUCLEO_F767ZI)
// For STM32F765VI in RemRam v1
// SRAM (0x20000000 - 0x20080000) (512kb)

View File

@ -97,7 +97,7 @@
#include "feature/closedloop.h"
#endif
#if HAS_I2C_DIGIPOT
#if HAS_MOTOR_CURRENT_I2C
#include "feature/digipot/digipot.h"
#endif
@ -125,7 +125,7 @@
#include "module/servo.h"
#endif
#if ENABLED(DAC_STEPPER_CURRENT)
#if ENABLED(HAS_MOTOR_CURRENT_DAC)
#include "feature/dac/stepper_dac.h"
#endif
@ -1048,6 +1048,11 @@ void setup() {
SERIAL_ECHO_MSG("Compiled: " __DATE__);
SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE));
// Init buzzer pin(s)
#if USE_BEEPER
SETUP_RUN(buzzer.init());
#endif
// Set up LEDs early
#if HAS_COLOR_LEDS
SETUP_RUN(leds.setup());
@ -1132,12 +1137,12 @@ void setup() {
SETUP_RUN(enableStepperDrivers());
#endif
#if HAS_I2C_DIGIPOT
SETUP_RUN(digipot_i2c_init());
#if HAS_MOTOR_CURRENT_I2C
SETUP_RUN(digipot_i2c.init());
#endif
#if ENABLED(DAC_STEPPER_CURRENT)
SETUP_RUN(dac_init());
#if ENABLED(HAS_MOTOR_CURRENT_DAC)
SETUP_RUN(stepper_dac.init());
#endif
#if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1

View File

@ -320,6 +320,7 @@
#define BOARD_CREALITY_V4 4034 // Creality v4.x (STM32F103RE)
#define BOARD_CREALITY_V427 4035 // Creality v4.2.7 (STM32F103RE)
#define BOARD_TRIGORILLA_PRO 4036 // Trigorilla Pro (STM32F103ZET6)
#define BOARD_FLY_MINI 4037 // FLY MINI (STM32F103RCT6)
//
// ARM Cortex-M4F
@ -362,6 +363,7 @@
#define BOARD_REMRAM_V1 5001 // RemRam v1
#define BOARD_TEENSY41 5002 // Teensy 4.1
#define BOARD_T41U5XBB 5003 // T41U5XBB Teensy 4.1 breakout board
#define BOARD_NUCLEO_F767ZI 5004 // ST NUCLEO-F767ZI Dev Board
//
// Espressif ESP32 WiFi

View File

@ -303,7 +303,7 @@
#define LCD_STR_C STR_C
#define LCD_STR_E STR_E
#if HAS_MARLINUI_HD44780
#if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
// Custom characters defined in the first 8 characters of the LCD
#define LCD_STR_BEDTEMP "\x00" // Print only as a char. This will have 'unexpected' results when used in a string!

View File

@ -215,6 +215,7 @@
#define WITHIN(N,L,H) ((N) >= (L) && (N) <= (H))
#define NUMERIC(a) WITHIN(a, '0', '9')
#define DECIMAL(a) (NUMERIC(a) || a == '.')
#define HEXCHR(a) (NUMERIC(a) ? (a) - '0' : WITHIN(a, 'a', 'f') ? ((a) - 'a' + 10) : WITHIN(a, 'A', 'F') ? ((a) - 'A' + 10) : -1)
#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+')
#define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+')
#define COUNT(a) (sizeof(a)/sizeof(*a))
@ -451,6 +452,12 @@
#define HAS_ARGS(V...) _BOOL(FIRST(_END_OF_ARGUMENTS_ V)())
#define _END_OF_ARGUMENTS_() 0
// Simple Inline IF Macros, friendly to use in other macro definitions
#define IF(O, A, B) ((O) ? (A) : (B))
#define IF_0(O, A) IF(O, A, 0)
#define IF_1(O, A) IF(O, A, 1)
//
// REPEAT core macros. Recurse N times with ascending I.
//

View File

@ -71,7 +71,7 @@ public:
inline void restore() { ref_ = val_; }
};
#define REMEMBER(N,X,V...) restorer<typeof(X)> restorer_##N(X, ##V)
#define REMEMBER(N,X,V...) restorer<__typeof__(X)> restorer_##N(X, ##V)
#define RESTORE(N) restorer_##N.restore()
// Converts from an uint8_t in the range of 0-255 to an uint8_t

View File

@ -1009,6 +1009,8 @@
lcd_mesh_edit_setup(new_z);
SET_SOFT_ENDSTOP_LOOSE(true);
do {
idle();
new_z = lcd_mesh_edit();
@ -1016,6 +1018,8 @@
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
} while (!ui.button_pressed());
SET_SOFT_ENDSTOP_LOOSE(false);
if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status
if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing

View File

@ -32,16 +32,18 @@
#include "../../inc/MarlinConfig.h"
#if ENABLED(DAC_STEPPER_CURRENT)
#if ENABLED(HAS_MOTOR_CURRENT_DAC)
#include "dac_mcp4728.h"
xyze_uint_t mcp4728_values;
MCP4728 mcp4728;
xyze_uint_t dac_values;
/**
* Begin I2C, get current values (input register and eeprom) of mcp4728
*/
void mcp4728_init() {
void MCP4728::init() {
Wire.begin();
Wire.requestFrom(I2C_ADDRESS(DAC_DEV_ADDRESS), uint8_t(24));
while (Wire.available()) {
@ -50,7 +52,7 @@ void mcp4728_init() {
loByte = Wire.read();
if (!(deviceID & 0x08))
mcp4728_values[(deviceID & 0x30) >> 4] = word((hiByte & 0x0F), loByte);
dac_values[(deviceID & 0x30) >> 4] = word((hiByte & 0x0F), loByte);
}
}
@ -58,9 +60,9 @@ void mcp4728_init() {
* Write input resister value to specified channel using fastwrite method.
* Channel : 0-3, Values : 0-4095
*/
uint8_t mcp4728_analogWrite(const uint8_t channel, const uint16_t value) {
mcp4728_values[channel] = value;
return mcp4728_fastWrite();
uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) {
dac_values[channel] = value;
return fastWrite();
}
/**
@ -68,12 +70,12 @@ uint8_t mcp4728_analogWrite(const uint8_t channel, const uint16_t value) {
* This will update both input register and EEPROM value
* This will also write current Vref, PowerDown, Gain settings to EEPROM
*/
uint8_t mcp4728_eepromWrite() {
uint8_t MCP4728::eepromWrite() {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(SEQWRITE);
LOOP_XYZE(i) {
Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(dac_values[i]));
Wire.write(lowByte(dac_values[i]));
}
return Wire.endTransmission();
}
@ -81,7 +83,7 @@ uint8_t mcp4728_eepromWrite() {
/**
* Write Voltage reference setting to all input regiters
*/
uint8_t mcp4728_setVref_all(const uint8_t value) {
uint8_t MCP4728::setVref_all(const uint8_t value) {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(VREFWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
@ -89,7 +91,7 @@ uint8_t mcp4728_setVref_all(const uint8_t value) {
/**
* Write Gain setting to all input regiters
*/
uint8_t mcp4728_setGain_all(const uint8_t value) {
uint8_t MCP4728::setGain_all(const uint8_t value) {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(GAINWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
@ -98,16 +100,16 @@ uint8_t mcp4728_setGain_all(const uint8_t value) {
/**
* Return Input Register value
*/
uint16_t mcp4728_getValue(const uint8_t channel) { return mcp4728_values[channel]; }
uint16_t MCP4728::getValue(const uint8_t channel) { return dac_values[channel]; }
#if 0
/**
* Steph: Might be useful in the future
* Return Vout
*/
uint16_t mcp4728_getVout(const uint8_t channel) {
uint16_t MCP4728::getVout(const uint8_t channel) {
const uint32_t vref = 2048,
vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
vOut = (vref * dac_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
return _MIN(vOut, defaultVDD);
}
#endif
@ -115,15 +117,15 @@ uint16_t mcp4728_getVout(const uint8_t channel) {
/**
* Returns DAC values as a 0-100 percentage of drive strength
*/
uint8_t mcp4728_getDrvPct(const uint8_t channel) { return uint8_t(100.0 * mcp4728_values[channel] / (DAC_STEPPER_MAX) + 0.5); }
uint8_t MCP4728::getDrvPct(const uint8_t channel) { return uint8_t(100.0 * dac_values[channel] / (DAC_STEPPER_MAX) + 0.5); }
/**
* Receives all Drive strengths as 0-100 percent values, updates
* DAC Values array and calls fastwrite to update the DAC.
*/
void mcp4728_setDrvPct(xyze_uint8_t &pct) {
mcp4728_values *= 0.01 * pct * (DAC_STEPPER_MAX);
mcp4728_fastWrite();
void MCP4728::setDrvPct(xyze_uint8_t &pct) {
dac_values *= 0.01 * pct * (DAC_STEPPER_MAX);
fastWrite();
}
/**
@ -131,11 +133,11 @@ void mcp4728_setDrvPct(xyze_uint8_t &pct) {
* DAC Input and PowerDown bits update.
* No EEPROM update
*/
uint8_t mcp4728_fastWrite() {
uint8_t MCP4728::fastWrite() {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
LOOP_XYZE(i) {
Wire.write(highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
Wire.write(highByte(dac_values[i]));
Wire.write(lowByte(dac_values[i]));
}
return Wire.endTransmission();
}
@ -143,10 +145,10 @@ uint8_t mcp4728_fastWrite() {
/**
* Common function for simple general commands
*/
uint8_t mcp4728_simpleCommand(const byte simpleCommand) {
uint8_t MCP4728::simpleCommand(const byte simpleCommand) {
Wire.beginTransmission(I2C_ADDRESS(GENERALCALL));
Wire.write(simpleCommand);
return Wire.endTransmission();
}
#endif // DAC_STEPPER_CURRENT
#endif // HAS_MOTOR_CURRENT_DAC

View File

@ -40,7 +40,7 @@
#endif
#ifndef lowByte
#define lowByte(w) ((uint8_t) ((w) & 0xff))
#define lowByte(w) ((uint8_t) ((w) & 0xFF))
#endif
#ifndef highByte
@ -65,13 +65,18 @@
// DAC_OR_ADDRESS defined in pins_BOARD.h file
#define DAC_DEV_ADDRESS (BASE_ADDR | DAC_OR_ADDRESS)
void mcp4728_init();
uint8_t mcp4728_analogWrite(const uint8_t channel, const uint16_t value);
uint8_t mcp4728_eepromWrite();
uint8_t mcp4728_setVref_all(const uint8_t value);
uint8_t mcp4728_setGain_all(const uint8_t value);
uint16_t mcp4728_getValue(const uint8_t channel);
uint8_t mcp4728_fastWrite();
uint8_t mcp4728_simpleCommand(const byte simpleCommand);
uint8_t mcp4728_getDrvPct(const uint8_t channel);
void mcp4728_setDrvPct(xyze_uint8_t &pct);
class MCP4728 {
public:
static void init();
static uint8_t analogWrite(const uint8_t channel, const uint16_t value);
static uint8_t eepromWrite();
static uint8_t setVref_all(const uint8_t value);
static uint8_t setGain_all(const uint8_t value);
static uint16_t getValue(const uint8_t channel);
static uint8_t fastWrite();
static uint8_t simpleCommand(const byte simpleCommand);
static uint8_t getDrvPct(const uint8_t channel);
static void setDrvPct(xyze_uint8_t &pct);
};
extern MCP4728 mcp4728;

View File

@ -26,7 +26,7 @@
#include "../../inc/MarlinConfig.h"
#if ENABLED(DAC_STEPPER_CURRENT)
#if ENABLED(HAS_MOTOR_CURRENT_DAC)
#include "stepper_dac.h"
#include "../../MarlinCore.h" // for SP_X_LBL...
@ -35,56 +35,53 @@ bool dac_present = false;
constexpr xyze_uint8_t dac_order = DAC_STEPPER_ORDER;
xyze_uint8_t dac_channel_pct = DAC_MOTOR_CURRENT_DEFAULT;
int dac_init() {
StepperDAC stepper_dac;
int StepperDAC::init() {
#if PIN_EXISTS(DAC_DISABLE)
OUT_WRITE(DAC_DISABLE_PIN, LOW); // set pin low to enable DAC
#endif
mcp4728_init();
mcp4728.init();
if (mcp4728_simpleCommand(RESET)) return -1;
if (mcp4728.simpleCommand(RESET)) return -1;
dac_present = true;
mcp4728_setVref_all(DAC_STEPPER_VREF);
mcp4728_setGain_all(DAC_STEPPER_GAIN);
mcp4728.setVref_all(DAC_STEPPER_VREF);
mcp4728.setGain_all(DAC_STEPPER_GAIN);
if (mcp4728_getDrvPct(0) < 1 || mcp4728_getDrvPct(1) < 1 || mcp4728_getDrvPct(2) < 1 || mcp4728_getDrvPct(3) < 1 ) {
mcp4728_setDrvPct(dac_channel_pct);
mcp4728_eepromWrite();
if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1 ) {
mcp4728.setDrvPct(dac_channel_pct);
mcp4728.eepromWrite();
}
return 0;
}
void dac_current_percent(uint8_t channel, float val) {
if (!dac_present) return;
NOMORE(val, 100);
mcp4728_analogWrite(dac_order[channel], val * 0.01 * (DAC_STEPPER_MAX));
mcp4728_simpleCommand(UPDATE);
}
void dac_current_raw(uint8_t channel, uint16_t val) {
void StepperDAC::set_current_value(const uint8_t channel, uint16_t val) {
if (!dac_present) return;
NOMORE(val, uint16_t(DAC_STEPPER_MAX));
mcp4728_analogWrite(dac_order[channel], val);
mcp4728_simpleCommand(UPDATE);
mcp4728.analogWrite(dac_order[channel], val);
mcp4728.simpleCommand(UPDATE);
}
static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * RECIPROCAL(DAC_STEPPER_MAX); }
static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * RECIPROCAL(DAC_STEPPER_SENSE); }
void StepperDAC::set_current_percent(const uint8_t channel, float val) {
set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) / 100.0f);
}
uint8_t dac_current_get_percent(const AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); }
void dac_current_set_percents(xyze_uint8_t &pct) {
static float dac_perc(int8_t n) { return 100.0 * mcp4728.getValue(dac_order[n]) * RECIPROCAL(DAC_STEPPER_MAX); }
static float dac_amps(int8_t n) { return mcp4728.getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * RECIPROCAL(DAC_STEPPER_SENSE); }
uint8_t StepperDAC::get_current_percent(const AxisEnum axis) { return mcp4728.getDrvPct(dac_order[axis]); }
void StepperDAC::set_current_percents(xyze_uint8_t &pct) {
LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]];
mcp4728_setDrvPct(dac_channel_pct);
mcp4728.setDrvPct(dac_channel_pct);
}
void dac_print_values() {
void StepperDAC::print_values() {
if (!dac_present) return;
SERIAL_ECHO_MSG("Stepper current values in % (Amps):");
SERIAL_ECHO_START();
@ -94,9 +91,9 @@ void dac_print_values() {
SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")"));
}
void dac_commit_eeprom() {
void StepperDAC::commit_eeprom() {
if (!dac_present) return;
mcp4728_eepromWrite();
mcp4728.eepromWrite();
}
#endif // DAC_STEPPER_CURRENT
#endif // HAS_MOTOR_CURRENT_DAC

View File

@ -27,10 +27,15 @@
#include "dac_mcp4728.h"
int dac_init();
void dac_current_percent(uint8_t channel, float val);
void dac_current_raw(uint8_t channel, uint16_t val);
void dac_print_values();
void dac_commit_eeprom();
uint8_t dac_current_get_percent(AxisEnum axis);
void dac_current_set_percents(xyze_uint8_t &pct);
class StepperDAC {
public:
static int init();
static void set_current_percent(const uint8_t channel, float val);
static void set_current_value(const uint8_t channel, uint16_t val);
static void print_values();
static void commit_eeprom();
static uint8_t get_current_percent(AxisEnum axis);
static void set_current_percents(xyze_uint8_t &pct);
};
extern StepperDAC stepper_dac;

View File

@ -21,5 +21,13 @@
*/
#pragma once
void digipot_i2c_set_current(const uint8_t channel, const float current);
void digipot_i2c_init();
//
// Header for MCP4018 and MCP4451 current control i2c devices
//
class DigipotI2C {
public:
static void init();
static void set_current(const uint8_t channel, const float current);
};
DigipotI2C digipot_i2c;

View File

@ -24,6 +24,8 @@
#if ENABLED(DIGIPOT_MCP4018)
#include "digipot.h"
#include <Stream.h>
#include <SlowSoftI2CMaster.h> // https://github.com/stawel/SlowSoftI2CMaster
@ -68,7 +70,7 @@ static SlowSoftI2CMaster pots[DIGIPOT_I2C_NUM_CHANNELS] = {
#endif
};
static void i2c_send(const uint8_t channel, const byte v) {
static void digipot_i2c_send(const uint8_t channel, const byte v) {
if (WITHIN(channel, 0, DIGIPOT_I2C_NUM_CHANNELS - 1)) {
pots[channel].i2c_start(((DIGIPOT_I2C_ADDRESS_A) << 1) | I2C_WRITE);
pots[channel].i2c_write(v);
@ -77,12 +79,12 @@ static void i2c_send(const uint8_t channel, const byte v) {
}
// This is for the MCP4018 I2C based digipot
void digipot_i2c_set_current(const uint8_t channel, const float current) {
void DigipotI2C::set_current(const uint8_t channel, const float current) {
const float ival = _MIN(_MAX(current, 0), float(DIGIPOT_MCP4018_MAX_VALUE));
i2c_send(channel, current_to_wiper(ival));
digipot_i2c_send(channel, current_to_wiper(ival));
}
void digipot_i2c_init() {
void DigipotI2C::init() {
LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init();
// Init currents according to Configuration_adv.h
@ -94,7 +96,7 @@ void digipot_i2c_init() {
#endif
;
LOOP_L_N(i, COUNT(digipot_motor_current))
digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i]));
set_current(i, pgm_read_float(&digipot_motor_current[i]));
}
#endif // DIGIPOT_MCP4018

View File

@ -24,6 +24,8 @@
#if ENABLED(DIGIPOT_MCP4451)
#include "digipot.h"
#include <Stream.h>
#include <Wire.h>
@ -61,7 +63,7 @@ static void digipot_i2c_send(const byte addr, const byte a, const byte b) {
}
// This is for the MCP4451 I2C based digipot
void digipot_i2c_set_current(const uint8_t channel, const float current) {
void DigipotI2C::set_current(const uint8_t channel, const float current) {
// These addresses are specific to Azteeg X3 Pro, can be set to others.
// In this case first digipot is at address A0=0, A1=0, second one is at A0=0, A1=1
const byte addr = channel < 4 ? DIGIPOT_I2C_ADDRESS_A : DIGIPOT_I2C_ADDRESS_B; // channel 0-3 vs 4-7
@ -75,7 +77,7 @@ void digipot_i2c_set_current(const uint8_t channel, const float current) {
digipot_i2c_send(addr, addresses[channel & 0x3], current_to_wiper(_MIN(float(_MAX(current, 0)), DIGIPOT_I2C_MAX_CURRENT)));
}
void digipot_i2c_init() {
void DigipotI2C::init() {
#if MB(MKS_SBASE)
configure_i2c(16); // Set clock_option to 16 ensure I2C is initialized at 400kHz
#else
@ -90,7 +92,7 @@ void digipot_i2c_init() {
#endif
;
LOOP_L_N(i, COUNT(digipot_motor_current))
digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i]));
set_current(i, pgm_read_float(&digipot_motor_current[i]));
}
#endif // DIGIPOT_MCP4451

View File

@ -88,10 +88,8 @@ public:
case EP_N:
switch (c) {
case '0': case '1': case '2':
case '3': case '4': case '5':
case '6': case '7': case '8':
case '9': case '-': case ' ': break;
case '0' ... '9':
case '-': case ' ': break;
case 'M': state = EP_M; break;
default: state = EP_IGNORE;
}
@ -153,10 +151,7 @@ public:
case EP_M876S:
switch (c) {
case ' ': break;
case '0': case '1': case '2':
case '3': case '4': case '5':
case '6': case '7': case '8':
case '9':
case '0' ... '9':
state = EP_M876SN;
M876_reason = (uint8_t)(c - '0');
break;

View File

@ -340,17 +340,17 @@ void MMU2::mmu_loop() {
#endif
if (rx_ok()) {
// response to C0 mmu command in PRUSA_MMU2_S_MODE
// Response to C0 mmu command in PRUSA_MMU2_S_MODE
bool can_reset = true;
if (ENABLED(PRUSA_MMU2_S_MODE) && last_cmd == MMU_CMD_C0) {
if (!mmu2s_triggered) {
#if ENABLED(PRUSA_MMU2_S_MODE)
if (!mmu2s_triggered && last_cmd == MMU_CMD_C0) {
can_reset = false;
// MMU ok received but filament sensor not triggered, retrying...
DEBUG_ECHOLNPGM("MMU => 'ok' (filament not present in gears)");
DEBUG_ECHOLNPGM("MMU <= 'C0' (keep trying)");
MMU2_COMMAND("C0");
}
}
#endif
if (can_reset) {
DEBUG_ECHOLNPGM("MMU => 'ok'");
ready = true;

View File

@ -61,6 +61,10 @@
#include "../libs/buzzer.h"
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
#include "powerloss.h"
#endif
#include "../libs/nozzle.h"
#include "pause.h"
@ -612,11 +616,13 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
// Retract to prevent oozing
unscaled_e_move(-(PAUSE_PARK_RETRACT_LENGTH), feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE));
// Move XY to starting position, then Z
do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE));
if (!axes_should_home()) {
// Move XY to starting position, then Z
do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE));
// Move Z_AXIS to saved position
do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE));
// Move Z_AXIS to saved position
do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE));
}
// Unretract
unscaled_e_move(PAUSE_PARK_RETRACT_LENGTH, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE));
@ -638,6 +644,9 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
// Set extruder to saved position
planner.set_e_position_mm((destination.e = current_position.e = resume_position.e));
// Write PLR now to update the z axis value
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS));
#ifdef ACTION_ON_RESUMED

View File

@ -38,7 +38,7 @@
#define CHOPPER_09STEP_24V { 3, -1, 5 }
#if ENABLED(MONITOR_DRIVER_STATUS) && !defined(MONITOR_DRIVER_STATUS_INTERVAL_MS)
#define MONITOR_DRIVER_STATUS_INTERVAL_MS 500u
#define MONITOR_DRIVER_STATUS_INTERVAL_MS 500U
#endif
constexpr uint16_t _tmc_thrs(const uint16_t msteps, const uint32_t thrs, const uint32_t spmm) {

View File

@ -511,11 +511,9 @@ void GcodeSuite::G26() {
g26_keep_heaters_on = parser.boolval('K');
// Accept 'I' if temperature presets are defined
const uint8_t preset_index = (0
#if PREHEAT_COUNT
+ (parser.seenval('I') ? _MIN(parser.value_byte(), PREHEAT_COUNT - 1) + 1 : 0)
#endif
);
#if PREHEAT_COUNT
const uint8_t preset_index = parser.seenval('I') ? _MIN(parser.value_byte(), PREHEAT_COUNT - 1) + 1 : 0;
#endif
#if HAS_HEATED_BED

View File

@ -157,9 +157,10 @@ void GcodeSuite::G35() {
const int minutes = trunc(decimal_part * 60.0f);
SERIAL_ECHOPAIR("Turn ", tramming_point_name[i],
" ", (screw_thread & 1) == (adjust > 0) ? "Counter-Clockwise" : "Clockwise",
" ", (screw_thread & 1) == (adjust > 0) ? "CCW" : "CW",
" by ", abs(full_turns), " turns");
if (minutes) SERIAL_ECHOPAIR(" and ", abs(minutes), " minutes");
if (ENABLED(REPORT_TRAMMING_MM)) SERIAL_ECHOPAIR(" (", -diff, "mm)");
SERIAL_EOL();
}
}

View File

@ -201,10 +201,6 @@ G29_TYPE GcodeSuite::G29() {
ABL_VAR int abl_probe_index;
#endif
#if BOTH(HAS_SOFTWARE_ENDSTOPS, PROBE_MANUALLY)
ABL_VAR bool saved_soft_endstops_state = true;
#endif
#if ABL_GRID
#if ENABLED(PROBE_MANUALLY)
@ -461,7 +457,7 @@ G29_TYPE GcodeSuite::G29() {
// Abort current G29 procedure, go back to idle state
if (seenA && g29_in_progress) {
SERIAL_ECHOLNPGM("Manual G29 aborted");
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
SET_SOFT_ENDSTOP_LOOSE(false);
set_bed_leveling_enabled(abl_should_enable);
g29_in_progress = false;
TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
@ -482,7 +478,7 @@ G29_TYPE GcodeSuite::G29() {
if (abl_probe_index == 0) {
// For the initial G29 S2 save software endstop state
TERN_(HAS_SOFTWARE_ENDSTOPS, saved_soft_endstops_state = soft_endstops_enabled);
SET_SOFT_ENDSTOP_LOOSE(true);
// Move close to the bed before the first point
do_blocking_move_to_z(0);
}
@ -552,14 +548,14 @@ G29_TYPE GcodeSuite::G29() {
_manual_goto_xy(probePos); // Can be used here too!
// Disable software endstops to allow manual adjustment
// If G29 is not completed, they will not be re-enabled
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false);
SET_SOFT_ENDSTOP_LOOSE(true);
G29_RETURN(false);
}
else {
// Leveling done! Fall through to G29 finishing code below
SERIAL_ECHOLNPGM("Grid probing done.");
// Re-enable software endstops, if needed
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
SET_SOFT_ENDSTOP_LOOSE(false);
}
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
@ -570,7 +566,7 @@ G29_TYPE GcodeSuite::G29() {
_manual_goto_xy(probePos);
// Disable software endstops to allow manual adjustment
// If G29 is not completed, they will not be re-enabled
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false);
SET_SOFT_ENDSTOP_LOOSE(true);
G29_RETURN(false);
}
else {
@ -578,7 +574,7 @@ G29_TYPE GcodeSuite::G29() {
SERIAL_ECHOLNPGM("3-point probing done.");
// Re-enable software endstops, if needed
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
SET_SOFT_ENDSTOP_LOOSE(false);
if (!dryrun) {
vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal();

View File

@ -61,7 +61,6 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM("
void GcodeSuite::G29() {
static int mbl_probe_index = -1;
TERN_(HAS_SOFTWARE_ENDSTOPS, static bool saved_soft_endstops_state);
MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport);
if (!WITHIN(state, 0, 5)) {
@ -98,26 +97,19 @@ void GcodeSuite::G29() {
}
// For each G29 S2...
if (mbl_probe_index == 0) {
#if HAS_SOFTWARE_ENDSTOPS
// For the initial G29 S2 save software endstop state
saved_soft_endstops_state = soft_endstops_enabled;
#endif
// Move close to the bed before the first point
do_blocking_move_to_z(0);
}
else {
// Save Z for the previous mesh position
mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z);
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
SET_SOFT_ENDSTOP_LOOSE(false);
}
// If there's another point to sample, move there with optional lift.
if (mbl_probe_index < GRID_MAX_POINTS) {
#if HAS_SOFTWARE_ENDSTOPS
// Disable software endstops to allow manual adjustment
// If G29 is not completed, they will not be re-enabled
soft_endstops_enabled = false;
#endif
// Disable software endstops to allow manual adjustment
// If G29 is left hanging without completion they won't be re-enabled!
SET_SOFT_ENDSTOP_LOOSE(true);
mbl.zigzag(mbl_probe_index++, ix, iy);
_manual_goto_xy({ mbl.index_to_xpos[ix], mbl.index_to_ypos[iy] });
}

View File

@ -222,8 +222,9 @@ void GcodeSuite::G28() {
return;
}
// Wait for planner moves to finish!
planner.synchronize();
planner.synchronize(); // Wait for planner moves to finish!
SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state
// Disable the leveling matrix before homing
#if HAS_LEVELING

Some files were not shown because too many files have changed in this diff Show More