Merge upstream changes from Marlin 2.1.2
This commit is contained in:
@@ -32,6 +32,7 @@
|
||||
#include <HardwareSerial.h>
|
||||
#else
|
||||
#include "MarlinSerial.h"
|
||||
#define BOARD_NO_NATIVE_USB
|
||||
#endif
|
||||
|
||||
#include <stdint.h>
|
||||
@@ -106,36 +107,36 @@ typedef Servo hal_servo_t;
|
||||
|
||||
#define MYSERIAL1 TERN(BLUETOOTH, btSerial, MSerial0)
|
||||
#else
|
||||
#if !WITHIN(SERIAL_PORT, -1, 3)
|
||||
#error "SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
|
||||
#if !WITHIN(SERIAL_PORT, 0, 3)
|
||||
#error "SERIAL_PORT must be from 0 to 3."
|
||||
#endif
|
||||
#define MYSERIAL1 customizedSerial1
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
#if !WITHIN(SERIAL_PORT_2, -1, 3)
|
||||
#error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial."
|
||||
#if !WITHIN(SERIAL_PORT_2, 0, 3)
|
||||
#error "SERIAL_PORT_2 must be from 0 to 3."
|
||||
#endif
|
||||
#define MYSERIAL2 customizedSerial2
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_3
|
||||
#if !WITHIN(SERIAL_PORT_3, -1, 3)
|
||||
#error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial."
|
||||
#if !WITHIN(SERIAL_PORT_3, 0, 3)
|
||||
#error "SERIAL_PORT_3 must be from 0 to 3."
|
||||
#endif
|
||||
#define MYSERIAL3 customizedSerial3
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef MMU2_SERIAL_PORT
|
||||
#if !WITHIN(MMU2_SERIAL_PORT, -1, 3)
|
||||
#error "MMU2_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
|
||||
#if !WITHIN(MMU2_SERIAL_PORT, 0, 3)
|
||||
#error "MMU2_SERIAL_PORT must be from 0 to 3"
|
||||
#endif
|
||||
#define MMU2_SERIAL mmuSerial
|
||||
#endif
|
||||
|
||||
#ifdef LCD_SERIAL_PORT
|
||||
#if !WITHIN(LCD_SERIAL_PORT, -1, 3)
|
||||
#error "LCD_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
|
||||
#if !WITHIN(LCD_SERIAL_PORT, 0, 3)
|
||||
#error "LCD_SERIAL_PORT must be from 0 to 3."
|
||||
#endif
|
||||
#define LCD_SERIAL lcdSerial
|
||||
#if HAS_DGUS_LCD
|
||||
|
@@ -146,10 +146,10 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
||||
LIMIT(res_pc_temp, 1U, maxtop);
|
||||
|
||||
// Calculate frequencies of test prescaler and resolution values
|
||||
const uint32_t f_diff = _MAX(f, f_desired) - _MIN(f, f_desired),
|
||||
f_fast_temp = (F_CPU) / (p * (1 + res_fast_temp)),
|
||||
const uint16_t f_fast_temp = (F_CPU) / (p * (1 + res_fast_temp)),
|
||||
f_pc_temp = (F_CPU) / (2 * p * res_pc_temp);
|
||||
const int f_diff = _MAX(f, f_desired) - _MIN(f, f_desired),
|
||||
f_fast_diff = _MAX(f_fast_temp, f_desired) - _MIN(f_fast_temp, f_desired),
|
||||
f_pc_temp = (F_CPU) / (2 * p * res_pc_temp),
|
||||
f_pc_diff = _MAX(f_pc_temp, f_desired) - _MIN(f_pc_temp, f_desired);
|
||||
|
||||
if (f_fast_diff < f_diff && f_fast_diff <= f_pc_diff) { // FAST values are closest to desired f
|
||||
|
@@ -293,11 +293,11 @@ enum ClockSource2 : uint8_t {
|
||||
|
||||
#if HAS_MOTOR_CURRENT_PWM
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_Z || P == MOTOR_CURRENT_PWM_XY)
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_E0 || P == MOTOR_CURRENT_PWM_E1 || P == MOTOR_CURRENT_PWM_Z || P == MOTOR_CURRENT_PWM_XY)
|
||||
#elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_Z)
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_E0 || P == MOTOR_CURRENT_PWM_E1 || P == MOTOR_CURRENT_PWM_Z)
|
||||
#else
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E)
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_E0 || P == MOTOR_CURRENT_PWM_E1)
|
||||
#endif
|
||||
#else
|
||||
#define PWM_CHK_MOTOR_CURRENT(P) false
|
||||
|
@@ -37,22 +37,24 @@
|
||||
|| X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \
|
||||
|| BTN_EN1 == N || BTN_EN2 == N \
|
||||
)
|
||||
#if CONF_SERIAL_IS(0)
|
||||
#if SERIAL_IN_USE(0)
|
||||
// D0-D1. No known conflicts.
|
||||
#endif
|
||||
#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__)
|
||||
#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19))
|
||||
#error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board."
|
||||
#endif
|
||||
#else
|
||||
#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(10) || CHECK_SERIAL_PIN(11))
|
||||
#error "Serial Port 1 pin D10 and/or D11 conflicts with another pin on the board."
|
||||
#if SERIAL_IN_USE(1)
|
||||
#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__)
|
||||
#if CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19)
|
||||
#error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board."
|
||||
#endif
|
||||
#else
|
||||
#if CHECK_SERIAL_PIN(10) || CHECK_SERIAL_PIN(11)
|
||||
#error "Serial Port 1 pin D10 and/or D11 conflicts with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
#if CONF_SERIAL_IS(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17))
|
||||
#if SERIAL_IN_USE(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17))
|
||||
#error "Serial Port 2 pin D16 and/or D17 conflicts with another pin on the board."
|
||||
#endif
|
||||
#if CONF_SERIAL_IS(3) && (CHECK_SERIAL_PIN(14) || CHECK_SERIAL_PIN(15))
|
||||
#if SERIAL_IN_USE(3) && (CHECK_SERIAL_PIN(14) || CHECK_SERIAL_PIN(15))
|
||||
#error "Serial Port 3 pin D14 and/or D15 conflicts with another pin on the board."
|
||||
#endif
|
||||
#undef CHECK_SERIAL_PIN
|
||||
|
@@ -210,7 +210,7 @@ public:
|
||||
static void adc_init() {}
|
||||
|
||||
// Called by Temperature::init for each sensor at startup
|
||||
static void adc_enable(const uint8_t ch) {}
|
||||
static void adc_enable(const uint8_t /*ch*/) {}
|
||||
|
||||
// Begin ADC sampling on the given channel. Called from Temperature::isr!
|
||||
static void adc_start(const uint8_t ch) { adc_result = analogRead(ch); }
|
||||
|
@@ -247,12 +247,12 @@
|
||||
b <<= 1; // little setup time
|
||||
|
||||
WRITE(SD_SCK_PIN, HIGH);
|
||||
DELAY_NS(spiDelayNS);
|
||||
DELAY_NS_VAR(spiDelayNS);
|
||||
|
||||
b |= (READ(SD_MISO_PIN) != 0);
|
||||
|
||||
WRITE(SD_SCK_PIN, LOW);
|
||||
DELAY_NS(spiDelayNS);
|
||||
DELAY_NS_VAR(spiDelayNS);
|
||||
} while (--bits);
|
||||
return b;
|
||||
}
|
||||
|
@@ -41,7 +41,7 @@
|
||||
practice, we need alignment to 256 bytes to make this work in all
|
||||
cases */
|
||||
__attribute__ ((aligned(256)))
|
||||
static DeviceVectors ram_tab = { nullptr };
|
||||
static DeviceVectors ram_tab[61] = { nullptr };
|
||||
|
||||
/**
|
||||
* This function checks if the exception/interrupt table is already in SRAM or not.
|
||||
|
@@ -36,15 +36,15 @@
|
||||
|| X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \
|
||||
|| X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \
|
||||
)
|
||||
#if CONF_SERIAL_IS(0) // D0-D1. No known conflicts.
|
||||
#if SERIAL_IN_USE(0) // D0-D1. No known conflicts.
|
||||
#endif
|
||||
#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19))
|
||||
#if SERIAL_IN_USE(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19))
|
||||
#error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board."
|
||||
#endif
|
||||
#if CONF_SERIAL_IS(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17))
|
||||
#if SERIAL_IN_USE(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17))
|
||||
#error "Serial Port 2 pin D16 and/or D17 conflicts with another pin on the board."
|
||||
#endif
|
||||
#if CONF_SERIAL_IS(3) && (CHECK_SERIAL_PIN(14) || CHECK_SERIAL_PIN(15))
|
||||
#if SERIAL_IN_USE(3) && (CHECK_SERIAL_PIN(14) || CHECK_SERIAL_PIN(15))
|
||||
#error "Serial Port 3 pin D14 and/or D15 conflicts with another pin on the board."
|
||||
#endif
|
||||
#undef CHECK_SERIAL_PIN
|
||||
|
@@ -70,7 +70,7 @@
|
||||
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define GET_ARRAY_PIN(p) pin_array[p].pin
|
||||
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0)
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
|
||||
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0))
|
||||
#define IS_ANALOG(P) WITHIN(P, char(analogInputToDigitalPin(0)), char(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
|
||||
#define pwm_status(pin) (((g_pinStatus[pin] & 0xF) == PIN_STATUS_PWM) && \
|
||||
|
@@ -6,14 +6,14 @@
|
||||
#
|
||||
import pioutil
|
||||
if pioutil.is_pio_build():
|
||||
import platform
|
||||
current_OS = platform.system()
|
||||
import platform
|
||||
current_OS = platform.system()
|
||||
|
||||
if current_OS == 'Windows':
|
||||
if current_OS == 'Windows':
|
||||
|
||||
Import("env")
|
||||
Import("env")
|
||||
|
||||
# Use bossac.exe on Windows
|
||||
env.Replace(
|
||||
UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE"
|
||||
)
|
||||
# Use bossac.exe on Windows
|
||||
env.Replace(
|
||||
UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE"
|
||||
)
|
||||
|
@@ -62,7 +62,7 @@ void usb_task_idle(void) {
|
||||
// Attend SD card access from the USB MSD -- Prioritize access to improve speed
|
||||
int delay = 2;
|
||||
while (main_b_msc_enable && --delay > 0) {
|
||||
if (udi_msc_process_trans()) delay = 10000;
|
||||
if (udi_msc_process_trans()) delay = 20;
|
||||
|
||||
// Reset the watchdog, just to be sure
|
||||
REG_WDT_CR = WDT_CR_WDRSTT | WDT_CR_KEY(0xA5);
|
||||
|
@@ -139,22 +139,40 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg) {
|
||||
}
|
||||
|
||||
void stepperTask(void *parameter) {
|
||||
uint32_t remaining = 0;
|
||||
uint32_t nextMainISR = 0;
|
||||
#if ENABLED(LIN_ADVANCE)
|
||||
uint32_t nextAdvanceISR = Stepper::LA_ADV_NEVER;
|
||||
#endif
|
||||
|
||||
while (1) {
|
||||
for (;;) {
|
||||
xQueueReceive(dma.queue, &dma.current, portMAX_DELAY);
|
||||
dma.rw_pos = 0;
|
||||
|
||||
while (dma.rw_pos < DMA_SAMPLE_COUNT) {
|
||||
// Fill with the port data post pulse_phase until the next step
|
||||
if (remaining) {
|
||||
if (nextMainISR && TERN1(LIN_ADVANCE, nextAdvanceISR))
|
||||
i2s_push_sample();
|
||||
remaining--;
|
||||
}
|
||||
else {
|
||||
|
||||
// i2s_push_sample() is also called from Stepper::pulse_phase_isr() and Stepper::advance_isr()
|
||||
// in a rare case where both are called, we need to double decrement the counters
|
||||
const uint8_t push_count = 1 + (!nextMainISR && TERN0(LIN_ADVANCE, !nextAdvanceISR));
|
||||
|
||||
#if ENABLED(LIN_ADVANCE)
|
||||
if (!nextAdvanceISR) {
|
||||
Stepper::advance_isr();
|
||||
nextAdvanceISR = Stepper::la_interval;
|
||||
}
|
||||
else if (nextAdvanceISR == Stepper::LA_ADV_NEVER)
|
||||
nextAdvanceISR = Stepper::la_interval;
|
||||
#endif
|
||||
|
||||
if (!nextMainISR) {
|
||||
Stepper::pulse_phase_isr();
|
||||
remaining = Stepper::block_phase_isr();
|
||||
nextMainISR = Stepper::block_phase_isr();
|
||||
}
|
||||
|
||||
nextMainISR -= push_count;
|
||||
TERN_(LIN_ADVANCE, nextAdvanceISR -= push_count);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@@ -45,10 +45,14 @@
|
||||
#error "FAST_PWM_FAN is not available on TinyBee."
|
||||
#endif
|
||||
|
||||
#if BOTH(I2S_STEPPER_STREAM, BABYSTEPPING) && DISABLED(INTEGRATED_BABYSTEPPING)
|
||||
#error "BABYSTEPPING on I2S stream requires INTEGRATED_BABYSTEPPING."
|
||||
#endif
|
||||
|
||||
#if USING_PULLDOWNS
|
||||
#error "PULLDOWN pin mode is not available on ESP32 boards."
|
||||
#endif
|
||||
|
||||
#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE)
|
||||
#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE) && DISABLED(EXPERIMENTAL_I2S_LA)
|
||||
#error "I2S stream is currently incompatible with LIN_ADVANCE."
|
||||
#endif
|
||||
|
@@ -32,6 +32,13 @@
|
||||
#include "HAL.h"
|
||||
#include "SPI.h"
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
#include "../../sd/cardreader.h"
|
||||
#if ENABLED(ESP3D_WIFISUPPORT)
|
||||
#include "sd_ESP32.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
static SPISettings spiConfig;
|
||||
|
||||
|
||||
@@ -45,6 +52,11 @@ static SPISettings spiConfig;
|
||||
|
||||
uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT
|
||||
|
||||
#if ENABLED(PAUSE_LCD_FOR_BUSY_SD)
|
||||
if (card.flag.saving || card.flag.logging || TERN0(ESP3D_WIFISUPPORT, sd_busy_lock == true)) return 0;
|
||||
#endif
|
||||
|
||||
if (msgInitCount) {
|
||||
if (msg == U8G_COM_MSG_INIT) msgInitCount--;
|
||||
if (msgInitCount) return -1;
|
||||
|
@@ -318,8 +318,16 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) {
|
||||
// Enable DMA
|
||||
GPDMA_ChannelCmd(0, ENABLE);
|
||||
|
||||
/*
|
||||
* Observed behaviour on normal data transfer completion (SKR 1.3 board / LPC1768 MCU)
|
||||
* GPDMA_STAT_INTTC flag is SET
|
||||
* GPDMA_STAT_INTERR flag is NOT SET
|
||||
* GPDMA_STAT_RAWINTTC flag is NOT SET
|
||||
* GPDMA_STAT_RAWINTERR flag is SET
|
||||
*/
|
||||
|
||||
// Wait for data transfer
|
||||
while (!GPDMA_IntGetStatus(GPDMA_STAT_RAWINTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_RAWINTERR, 0)) { }
|
||||
while (!GPDMA_IntGetStatus(GPDMA_STAT_INTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_INTERR, 0)) {}
|
||||
|
||||
// Clear err and int
|
||||
GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0);
|
||||
@@ -333,6 +341,43 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) {
|
||||
SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, DISABLE);
|
||||
}
|
||||
|
||||
void SPIClass::dmaSendAsync(void *buf, uint16_t length, bool minc) {
|
||||
//TODO: LPC dma can only write 0xFFF bytes at once.
|
||||
GPDMA_Channel_CFG_Type GPDMACfg;
|
||||
|
||||
/* Configure GPDMA channel 0 -------------------------------------------------------------*/
|
||||
/* DMA Channel 0 */
|
||||
GPDMACfg.ChannelNum = 0;
|
||||
// Source memory
|
||||
GPDMACfg.SrcMemAddr = (uint32_t)buf;
|
||||
// Destination memory - Not used
|
||||
GPDMACfg.DstMemAddr = 0;
|
||||
// Transfer size
|
||||
GPDMACfg.TransferSize = length;
|
||||
// Transfer width
|
||||
GPDMACfg.TransferWidth = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? GPDMA_WIDTH_HALFWORD : GPDMA_WIDTH_BYTE;
|
||||
// Transfer type
|
||||
GPDMACfg.TransferType = GPDMA_TRANSFERTYPE_M2P;
|
||||
// Source connection - unused
|
||||
GPDMACfg.SrcConn = 0;
|
||||
// Destination connection
|
||||
GPDMACfg.DstConn = (_currentSetting->spi_d == LPC_SSP0) ? GPDMA_CONN_SSP0_Tx : GPDMA_CONN_SSP1_Tx;
|
||||
|
||||
GPDMACfg.DMALLI = 0;
|
||||
|
||||
// Enable dma on SPI
|
||||
SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, ENABLE);
|
||||
|
||||
// Only increase memory if minc is true
|
||||
GPDMACfg.MemoryIncrease = (minc ? GPDMA_DMACCxControl_SI : 0);
|
||||
|
||||
// Setup channel with given parameter
|
||||
GPDMA_Setup(&GPDMACfg);
|
||||
|
||||
// Enable DMA
|
||||
GPDMA_ChannelCmd(0, ENABLE);
|
||||
}
|
||||
|
||||
uint16_t SPIClass::read() {
|
||||
return SSP_ReceiveData(_currentSetting->spi_d);
|
||||
}
|
||||
|
@@ -29,6 +29,6 @@
|
||||
|
||||
// LPC1768 boards seem to lose steps when saving to EEPROM during print (issue #20785)
|
||||
// TODO: Which other boards are incompatible?
|
||||
#if defined(MCU_LPC1768) && PRINTCOUNTER_SAVE_INTERVAL > 0
|
||||
#if defined(MCU_LPC1768) && ENABLED(FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0
|
||||
#define PRINTCOUNTER_SYNC 1
|
||||
#endif
|
||||
|
@@ -155,6 +155,7 @@ public:
|
||||
void read(uint8_t *buf, uint32_t len);
|
||||
|
||||
void dmaSend(void *buf, uint16_t length, bool minc);
|
||||
void dmaSendAsync(void *buf, uint16_t length, bool minc);
|
||||
|
||||
/**
|
||||
* @brief Sets the number of the SPI peripheral to be used by
|
||||
|
@@ -26,7 +26,7 @@
|
||||
|
||||
#include "tft_spi.h"
|
||||
|
||||
SPIClass TFT_SPI::SPIx(1);
|
||||
SPIClass TFT_SPI::SPIx(TFT_SPI_DEVICE);
|
||||
|
||||
void TFT_SPI::Init() {
|
||||
#if PIN_EXISTS(TFT_RESET)
|
||||
@@ -38,40 +38,10 @@ void TFT_SPI::Init() {
|
||||
OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
|
||||
#endif
|
||||
|
||||
SET_OUTPUT(TFT_DC_PIN);
|
||||
SET_OUTPUT(TFT_CS_PIN);
|
||||
WRITE(TFT_DC_PIN, HIGH);
|
||||
WRITE(TFT_CS_PIN, HIGH);
|
||||
OUT_WRITE(TFT_DC_PIN, HIGH);
|
||||
OUT_WRITE(TFT_CS_PIN, HIGH);
|
||||
|
||||
/**
|
||||
* STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz
|
||||
* STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1
|
||||
* so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2
|
||||
*/
|
||||
#if 0
|
||||
#if SPI_DEVICE == 1
|
||||
#define SPI_CLOCK_MAX SPI_CLOCK_DIV4
|
||||
#else
|
||||
#define SPI_CLOCK_MAX SPI_CLOCK_DIV2
|
||||
#endif
|
||||
uint8_t clock;
|
||||
uint8_t spiRate = SPI_FULL_SPEED;
|
||||
switch (spiRate) {
|
||||
case SPI_FULL_SPEED: clock = SPI_CLOCK_MAX ; break;
|
||||
case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break;
|
||||
case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break;
|
||||
case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break;
|
||||
case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break;
|
||||
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
|
||||
default: clock = SPI_CLOCK_DIV2; // Default from the SPI library
|
||||
}
|
||||
#endif
|
||||
|
||||
#if TFT_MISO_PIN == BOARD_SPI1_MISO_PIN
|
||||
SPIx.setModule(1);
|
||||
#elif TFT_MISO_PIN == BOARD_SPI2_MISO_PIN
|
||||
SPIx.setModule(2);
|
||||
#endif
|
||||
SPIx.setModule(TFT_SPI_DEVICE);
|
||||
SPIx.setClock(SPI_CLOCK_MAX_TFT);
|
||||
SPIx.setBitOrder(MSBFIRST);
|
||||
SPIx.setDataMode(SPI_MODE0);
|
||||
@@ -114,17 +84,62 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
|
||||
return data >> 7;
|
||||
}
|
||||
|
||||
bool TFT_SPI::isBusy() { return false; }
|
||||
bool TFT_SPI::isBusy() {
|
||||
#define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->DMACCSrcAddr != 0)
|
||||
|
||||
void TFT_SPI::Abort() { DataTransferEnd(); }
|
||||
// DMA Channel 0 is hardcoded in dmaSendAsync() and dmaSend()
|
||||
if (!__IS_DMA_CONFIGURED(LPC_GPDMACH0)) return false;
|
||||
|
||||
void TFT_SPI::Transmit(uint16_t Data) { SPIx.transfer(Data); }
|
||||
if (GPDMA_IntGetStatus(GPDMA_STAT_INTERR, 0)) {
|
||||
// You should not be here - DMA transfer error flag is set
|
||||
// Abort DMA transfer and release SPI
|
||||
}
|
||||
else {
|
||||
// Check if DMA transfer completed flag is set
|
||||
if (!GPDMA_IntGetStatus(GPDMA_STAT_INTTC, 0)) return true;
|
||||
// Check if SPI TX butter is empty and SPI is idle
|
||||
if ((SSP_GetStatus(LPC_SSPx, SSP_STAT_TXFIFO_EMPTY) == RESET) || (SSP_GetStatus(LPC_SSPx, SSP_STAT_BUSY) == SET)) return true;
|
||||
}
|
||||
|
||||
Abort();
|
||||
return false;
|
||||
}
|
||||
|
||||
void TFT_SPI::Abort() {
|
||||
// DMA Channel 0 is hardcoded in dmaSendAsync() and dmaSend()
|
||||
|
||||
// Disable DMA
|
||||
GPDMA_ChannelCmd(0, DISABLE);
|
||||
|
||||
// Clear ERR and TC
|
||||
GPDMA_ClearIntPending(GPDMA_STATCLR_INTTC, 0);
|
||||
GPDMA_ClearIntPending(GPDMA_STATCLR_INTERR, 0);
|
||||
|
||||
// Disable DMA on SPI
|
||||
SSP_DMACmd(LPC_SSPx, SSP_DMA_TX, DISABLE);
|
||||
|
||||
// Deconfigure DMA Channel 0
|
||||
LPC_GPDMACH0->DMACCControl = 0U;
|
||||
LPC_GPDMACH0->DMACCConfig = 0U;
|
||||
LPC_GPDMACH0->DMACCSrcAddr = 0U;
|
||||
LPC_GPDMACH0->DMACCDestAddr = 0U;
|
||||
|
||||
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DataTransferBegin(DATASIZE_16BIT);
|
||||
WRITE(TFT_DC_PIN, HIGH);
|
||||
SPIx.dmaSend(Data, Count, MemoryIncrease);
|
||||
DataTransferEnd();
|
||||
}
|
||||
|
||||
void TFT_SPI::Transmit(uint16_t Data) { SPIx.transfer(Data); }
|
||||
|
||||
void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DataTransferBegin(DATASIZE_16BIT);
|
||||
SPIx.dmaSend(Data, Count, MemoryIncrease);
|
||||
Abort();
|
||||
}
|
||||
|
||||
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DataTransferBegin(DATASIZE_16BIT);
|
||||
SPIx.dmaSendAsync(Data, Count, MemoryIncrease);
|
||||
|
||||
TERN_(TFT_SHARED_SPI, while (isBusy()));
|
||||
}
|
||||
|
||||
#endif // HAS_SPI_TFT
|
||||
|
@@ -27,6 +27,18 @@
|
||||
#include <lpc17xx_ssp.h>
|
||||
// #include <lpc17xx_gpdma.h>
|
||||
|
||||
#define IS_SPI(N) (BOARD_NR_SPI >= N && (TFT_SCK_PIN == BOARD_SPI##N##_SCK_PIN) && (TFT_MOSI_PIN == BOARD_SPI##N##_MOSI_PIN) && (TFT_MISO_PIN == BOARD_SPI##N##_MISO_PIN))
|
||||
#if IS_SPI(1)
|
||||
#define TFT_SPI_DEVICE 1
|
||||
#define LPC_SSPx LPC_SSP0
|
||||
#elif IS_SPI(2)
|
||||
#define TFT_SPI_DEVICE 2
|
||||
#define LPC_SSPx LPC_SSP1
|
||||
#else
|
||||
#error "Invalid TFT SPI configuration."
|
||||
#endif
|
||||
#undef IS_SPI
|
||||
|
||||
#ifndef LCD_READ_ID
|
||||
#define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
@@ -34,17 +46,19 @@
|
||||
#define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
|
||||
#define DATASIZE_8BIT SSP_DATABIT_8
|
||||
#define DATASIZE_16BIT SSP_DATABIT_16
|
||||
#define TFT_IO_DRIVER TFT_SPI
|
||||
#define DATASIZE_8BIT SSP_DATABIT_8
|
||||
#define DATASIZE_16BIT SSP_DATABIT_16
|
||||
#define TFT_IO_DRIVER TFT_SPI
|
||||
#define DMA_MAX_SIZE 0xFFF
|
||||
|
||||
#define DMA_MINC_ENABLE 1
|
||||
#define DMA_MINC_DISABLE 0
|
||||
#define DMA_MINC_ENABLE 1
|
||||
#define DMA_MINC_DISABLE 0
|
||||
|
||||
class TFT_SPI {
|
||||
private:
|
||||
static uint32_t ReadID(uint16_t Reg);
|
||||
static void Transmit(uint16_t Data);
|
||||
static void Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
@@ -56,22 +70,20 @@ public:
|
||||
static void Abort();
|
||||
|
||||
static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT);
|
||||
static void DataTransferEnd() { OUT_WRITE(TFT_CS_PIN, HIGH); SPIx.end(); };
|
||||
static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); SSP_Cmd(LPC_SSPx, DISABLE); };
|
||||
static void DataTransferAbort();
|
||||
|
||||
static void WriteData(uint16_t Data) { Transmit(Data); }
|
||||
static void WriteReg(uint16_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); }
|
||||
static void WriteReg(uint16_t Reg) { WRITE(TFT_DC_PIN, LOW); Transmit(Reg); WRITE(TFT_DC_PIN, HIGH); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
// static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
static void WriteSequence_DMA(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple_DMA(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
//LPC dma can only write 0xFFF bytes at once.
|
||||
#define MAX_DMA_SIZE (0xFFF - 1)
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > MAX_DMA_SIZE ? MAX_DMA_SIZE : Count);
|
||||
Count = Count > MAX_DMA_SIZE ? Count - MAX_DMA_SIZE : 0;
|
||||
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
|
||||
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
|
||||
}
|
||||
#undef MAX_DMA_SIZE
|
||||
}
|
||||
};
|
||||
|
@@ -44,9 +44,11 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; }
|
||||
#endif
|
||||
|
||||
void XPT2046::Init() {
|
||||
SET_INPUT(TOUCH_MISO_PIN);
|
||||
SET_OUTPUT(TOUCH_MOSI_PIN);
|
||||
SET_OUTPUT(TOUCH_SCK_PIN);
|
||||
#if DISABLED(TOUCH_BUTTONS_HW_SPI)
|
||||
SET_INPUT(TOUCH_MISO_PIN);
|
||||
SET_OUTPUT(TOUCH_MOSI_PIN);
|
||||
SET_OUTPUT(TOUCH_SCK_PIN);
|
||||
#endif
|
||||
OUT_WRITE(TOUCH_CS_PIN, HIGH);
|
||||
|
||||
#if PIN_EXISTS(TOUCH_INT)
|
||||
|
@@ -9,127 +9,127 @@ from __future__ import print_function
|
||||
import pioutil
|
||||
if pioutil.is_pio_build():
|
||||
|
||||
target_filename = "FIRMWARE.CUR"
|
||||
target_drive = "REARM"
|
||||
target_filename = "FIRMWARE.CUR"
|
||||
target_drive = "REARM"
|
||||
|
||||
import platform
|
||||
import platform
|
||||
|
||||
current_OS = platform.system()
|
||||
Import("env")
|
||||
current_OS = platform.system()
|
||||
Import("env")
|
||||
|
||||
def print_error(e):
|
||||
print('\nUnable to find destination disk (%s)\n' \
|
||||
'Please select it in platformio.ini using the upload_port keyword ' \
|
||||
'(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \
|
||||
'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \
|
||||
%(e, env.get('PIOENV')))
|
||||
def print_error(e):
|
||||
print('\nUnable to find destination disk (%s)\n' \
|
||||
'Please select it in platformio.ini using the upload_port keyword ' \
|
||||
'(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \
|
||||
'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \
|
||||
%(e, env.get('PIOENV')))
|
||||
|
||||
def before_upload(source, target, env):
|
||||
try:
|
||||
from pathlib import Path
|
||||
#
|
||||
# Find a disk for upload
|
||||
#
|
||||
upload_disk = 'Disk not found'
|
||||
target_file_found = False
|
||||
target_drive_found = False
|
||||
if current_OS == 'Windows':
|
||||
#
|
||||
# platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:'
|
||||
# Windows - doesn't care about the disk's name, only cares about the drive letter
|
||||
import subprocess,string
|
||||
from ctypes import windll
|
||||
from pathlib import PureWindowsPath
|
||||
def before_upload(source, target, env):
|
||||
try:
|
||||
from pathlib import Path
|
||||
#
|
||||
# Find a disk for upload
|
||||
#
|
||||
upload_disk = 'Disk not found'
|
||||
target_file_found = False
|
||||
target_drive_found = False
|
||||
if current_OS == 'Windows':
|
||||
#
|
||||
# platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:'
|
||||
# Windows - doesn't care about the disk's name, only cares about the drive letter
|
||||
import subprocess,string
|
||||
from ctypes import windll
|
||||
from pathlib import PureWindowsPath
|
||||
|
||||
# getting list of drives
|
||||
# https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python
|
||||
drives = []
|
||||
bitmask = windll.kernel32.GetLogicalDrives()
|
||||
for letter in string.ascii_uppercase:
|
||||
if bitmask & 1:
|
||||
drives.append(letter)
|
||||
bitmask >>= 1
|
||||
# getting list of drives
|
||||
# https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python
|
||||
drives = []
|
||||
bitmask = windll.kernel32.GetLogicalDrives()
|
||||
for letter in string.ascii_uppercase:
|
||||
if bitmask & 1:
|
||||
drives.append(letter)
|
||||
bitmask >>= 1
|
||||
|
||||
for drive in drives:
|
||||
final_drive_name = drive + ':'
|
||||
# print ('disc check: {}'.format(final_drive_name))
|
||||
try:
|
||||
volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT))
|
||||
except Exception as e:
|
||||
print ('error:{}'.format(e))
|
||||
continue
|
||||
else:
|
||||
if target_drive in volume_info and not target_file_found: # set upload if not found target file yet
|
||||
target_drive_found = True
|
||||
upload_disk = PureWindowsPath(final_drive_name)
|
||||
if target_filename in volume_info:
|
||||
if not target_file_found:
|
||||
upload_disk = PureWindowsPath(final_drive_name)
|
||||
target_file_found = True
|
||||
for drive in drives:
|
||||
final_drive_name = drive + ':'
|
||||
# print ('disc check: {}'.format(final_drive_name))
|
||||
try:
|
||||
volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT))
|
||||
except Exception as e:
|
||||
print ('error:{}'.format(e))
|
||||
continue
|
||||
else:
|
||||
if target_drive in volume_info and not target_file_found: # set upload if not found target file yet
|
||||
target_drive_found = True
|
||||
upload_disk = PureWindowsPath(final_drive_name)
|
||||
if target_filename in volume_info:
|
||||
if not target_file_found:
|
||||
upload_disk = PureWindowsPath(final_drive_name)
|
||||
target_file_found = True
|
||||
|
||||
elif current_OS == 'Linux':
|
||||
#
|
||||
# platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive'
|
||||
#
|
||||
import getpass
|
||||
user = getpass.getuser()
|
||||
mpath = Path('media', user)
|
||||
drives = [ x for x in mpath.iterdir() if x.is_dir() ]
|
||||
if target_drive in drives: # If target drive is found, use it.
|
||||
target_drive_found = True
|
||||
upload_disk = mpath / target_drive
|
||||
else:
|
||||
for drive in drives:
|
||||
try:
|
||||
fpath = mpath / drive
|
||||
files = [ x for x in fpath.iterdir() if x.is_file() ]
|
||||
except:
|
||||
continue
|
||||
else:
|
||||
if target_filename in files:
|
||||
upload_disk = mpath / drive
|
||||
target_file_found = True
|
||||
break
|
||||
#
|
||||
# set upload_port to drive if found
|
||||
#
|
||||
elif current_OS == 'Linux':
|
||||
#
|
||||
# platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive'
|
||||
#
|
||||
import getpass
|
||||
user = getpass.getuser()
|
||||
mpath = Path('/media', user)
|
||||
drives = [ x for x in mpath.iterdir() if x.is_dir() ]
|
||||
if target_drive in drives: # If target drive is found, use it.
|
||||
target_drive_found = True
|
||||
upload_disk = mpath / target_drive
|
||||
else:
|
||||
for drive in drives:
|
||||
try:
|
||||
fpath = mpath / drive
|
||||
filenames = [ x.name for x in fpath.iterdir() if x.is_file() ]
|
||||
except:
|
||||
continue
|
||||
else:
|
||||
if target_filename in filenames:
|
||||
upload_disk = mpath / drive
|
||||
target_file_found = True
|
||||
break
|
||||
#
|
||||
# set upload_port to drive if found
|
||||
#
|
||||
|
||||
if target_file_found or target_drive_found:
|
||||
env.Replace(
|
||||
UPLOAD_FLAGS="-P$UPLOAD_PORT"
|
||||
)
|
||||
if target_file_found or target_drive_found:
|
||||
env.Replace(
|
||||
UPLOAD_FLAGS="-P$UPLOAD_PORT"
|
||||
)
|
||||
|
||||
elif current_OS == 'Darwin': # MAC
|
||||
#
|
||||
# platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive'
|
||||
#
|
||||
dpath = Path('/Volumes') # human readable names
|
||||
drives = [ x for x in dpath.iterdir() ]
|
||||
if target_drive in drives and not target_file_found: # set upload if not found target file yet
|
||||
target_drive_found = True
|
||||
upload_disk = dpath / target_drive
|
||||
for drive in drives:
|
||||
try:
|
||||
fpath = dpath / drive # will get an error if the drive is protected
|
||||
files = [ x for x in fpath.iterdir() ]
|
||||
except:
|
||||
continue
|
||||
else:
|
||||
if target_filename in files:
|
||||
if not target_file_found:
|
||||
upload_disk = dpath / drive
|
||||
target_file_found = True
|
||||
elif current_OS == 'Darwin': # MAC
|
||||
#
|
||||
# platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive'
|
||||
#
|
||||
dpath = Path('/Volumes') # human readable names
|
||||
drives = [ x for x in dpath.iterdir() if x.is_dir() ]
|
||||
if target_drive in drives and not target_file_found: # set upload if not found target file yet
|
||||
target_drive_found = True
|
||||
upload_disk = dpath / target_drive
|
||||
for drive in drives:
|
||||
try:
|
||||
fpath = dpath / drive # will get an error if the drive is protected
|
||||
filenames = [ x.name for x in fpath.iterdir() if x.is_file() ]
|
||||
except:
|
||||
continue
|
||||
else:
|
||||
if target_filename in filenames:
|
||||
upload_disk = dpath / drive
|
||||
target_file_found = True
|
||||
break
|
||||
|
||||
#
|
||||
# Set upload_port to drive if found
|
||||
#
|
||||
if target_file_found or target_drive_found:
|
||||
env.Replace(UPLOAD_PORT=str(upload_disk))
|
||||
print('\nUpload disk: ', upload_disk, '\n')
|
||||
else:
|
||||
print_error('Autodetect Error')
|
||||
#
|
||||
# Set upload_port to drive if found
|
||||
#
|
||||
if target_file_found or target_drive_found:
|
||||
env.Replace(UPLOAD_PORT=str(upload_disk))
|
||||
print('\nUpload disk: ', upload_disk, '\n')
|
||||
else:
|
||||
print_error('Autodetect Error')
|
||||
|
||||
except Exception as e:
|
||||
print_error(str(e))
|
||||
except Exception as e:
|
||||
print_error(str(e))
|
||||
|
||||
env.AddPreAction("upload", before_upload)
|
||||
env.AddPreAction("upload", before_upload)
|
||||
|
@@ -44,7 +44,7 @@
|
||||
*
|
||||
* Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW);
|
||||
*
|
||||
* Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
|
||||
* Why double up on these macros? see https://gcc.gnu.org/onlinedocs/cpp/Stringification.html
|
||||
*/
|
||||
|
||||
/// Read a pin
|
||||
|
@@ -51,7 +51,7 @@ enum XPTCoordinate : uint8_t {
|
||||
XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE,
|
||||
};
|
||||
|
||||
#if !defined(XPT2046_Z1_THRESHOLD)
|
||||
#ifndef XPT2046_Z1_THRESHOLD
|
||||
#define XPT2046_Z1_THRESHOLD 10
|
||||
#endif
|
||||
|
||||
|
@@ -168,4 +168,4 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void
|
||||
#endif
|
||||
|
||||
#endif // IS_U8GLIB_ST7920
|
||||
#endif // TARGET_LPC1768
|
||||
#endif // __PLAT_NATIVE_SIM__
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,10 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
#ifdef __SAMD51__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#define CPU_32_BIT
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -19,6 +20,10 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
/**
|
||||
* Hardware and software SPI implementations are included in this file.
|
||||
*
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,10 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
#ifdef ADAFRUIT_GRAND_CENTRAL_M4
|
||||
|
||||
/**
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#include "../../core/serial_hook.h"
|
||||
|
||||
typedef Serial1Class<Uart> UartT;
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#define SYNC(sc) while (sc) { \
|
||||
asm(""); \
|
||||
}
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -19,6 +20,10 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
/**
|
||||
* This comes from Arduino library which at the moment is buggy and uncompilable
|
||||
*/
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#define _useTimer1
|
||||
#define _useTimer2
|
||||
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,10 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
#ifdef __SAMD51__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,10 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
#ifdef __SAMD51__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,10 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
#ifdef __SAMD51__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
/**
|
||||
* Endstop interrupts for ATMEL SAMD51 based targets.
|
||||
*
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
/**
|
||||
* Fast IO functions for SAMD51
|
||||
*/
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,11 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
/**
|
||||
* Test SAMD51 specific configuration values for errors at compile-time.
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL PINS_COUNT
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
@@ -29,7 +34,7 @@
|
||||
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define GET_ARRAY_PIN(p) pin_array[p].pin
|
||||
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL)
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
|
||||
#define DIGITAL_PIN_TO_ANALOG_PIN(p) digitalPinToAnalogInput(p)
|
||||
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P)!=-1)
|
||||
#define pwm_status(pin) digitalPinHasPWM(pin)
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#ifdef ADAFRUIT_GRAND_CENTRAL_M4
|
||||
|
||||
/*
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -18,6 +19,10 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
#ifdef __SAMD51__
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
@@ -1,8 +1,9 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
@@ -20,6 +21,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
@@ -95,7 +95,7 @@
|
||||
static_assert(IS_FLASH_SECTOR(FLASH_SECTOR), "FLASH_SECTOR is invalid");
|
||||
static_assert(IS_POWER_OF_2(FLASH_UNIT_SIZE), "FLASH_UNIT_SIZE should be a power of 2, please check your chip's spec sheet");
|
||||
|
||||
#endif
|
||||
#endif // FLASH_EEPROM_LEVELING
|
||||
|
||||
static bool eeprom_data_written = false;
|
||||
|
||||
@@ -189,15 +189,15 @@ bool PersistentStore::access_finish() {
|
||||
|
||||
UNLOCK_FLASH();
|
||||
|
||||
uint32_t offset = 0;
|
||||
uint32_t address = SLOT_ADDRESS(current_slot);
|
||||
uint32_t address_end = address + MARLIN_EEPROM_SIZE;
|
||||
uint32_t data = 0;
|
||||
uint32_t offset = 0,
|
||||
address = SLOT_ADDRESS(current_slot),
|
||||
address_end = address + MARLIN_EEPROM_SIZE,
|
||||
data = 0;
|
||||
|
||||
bool success = true;
|
||||
|
||||
while (address < address_end) {
|
||||
memcpy(&data, ram_eeprom + offset, sizeof(uint32_t));
|
||||
memcpy(&data, ram_eeprom + offset, sizeof(data));
|
||||
status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, data);
|
||||
if (status == HAL_OK) {
|
||||
address += sizeof(uint32_t);
|
||||
@@ -221,7 +221,8 @@ bool PersistentStore::access_finish() {
|
||||
|
||||
return success;
|
||||
|
||||
#else
|
||||
#else // !FLASH_EEPROM_LEVELING
|
||||
|
||||
// The following was written for the STM32F4 but may work with other MCUs as well.
|
||||
// Most STM32F4 flash does not allow reading from flash during erase operations.
|
||||
// This takes about a second on a STM32F407 with a 128kB sector used as EEPROM.
|
||||
@@ -235,7 +236,8 @@ bool PersistentStore::access_finish() {
|
||||
TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
|
||||
|
||||
eeprom_data_written = false;
|
||||
#endif
|
||||
|
||||
#endif // !FLASH_EEPROM_LEVELING
|
||||
}
|
||||
|
||||
return true;
|
||||
|
@@ -27,3 +27,8 @@
|
||||
#elif EITHER(I2C_EEPROM, SPI_EEPROM)
|
||||
#define USE_SHARED_EEPROM 1
|
||||
#endif
|
||||
|
||||
// Some STM32F4 boards may lose steps when saving to EEPROM during print (PR #17946)
|
||||
#if defined(STM32F4xx) && ENABLED(FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0
|
||||
#define PRINTCOUNTER_SYNC 1
|
||||
#endif
|
||||
|
@@ -37,11 +37,6 @@
|
||||
#error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4xx) && BOTH(PRINTCOUNTER, FLASH_EEPROM_EMULATION)
|
||||
#warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing."
|
||||
#error "Disable PRINTCOUNTER or choose another EEPROM emulation."
|
||||
#endif
|
||||
|
||||
#if !defined(STM32F4xx) && ENABLED(FLASH_EEPROM_LEVELING)
|
||||
#error "FLASH_EEPROM_LEVELING is currently only supported on STM32F4 hardware."
|
||||
#endif
|
||||
@@ -55,3 +50,62 @@
|
||||
#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32H7xx, STM32F4xx, STM32F1xx)
|
||||
#error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32H7, STM32F4 and STM32F1 hardware."
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Check for common serial pin conflicts
|
||||
*/
|
||||
#define _CHECK_SERIAL_PIN(N) (( \
|
||||
BTN_EN1 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN_PIN == N || \
|
||||
SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N \
|
||||
))
|
||||
#define CHECK_SERIAL_PIN(T,N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN)
|
||||
#if SERIAL_IN_USE(1)
|
||||
#if CHECK_SERIAL_PIN(TX,1)
|
||||
#error "Serial Port 1 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX,1)
|
||||
#error "Serial Port 1 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#if SERIAL_IN_USE(2)
|
||||
#if CHECK_SERIAL_PIN(TX,2)
|
||||
#error "Serial Port 2 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX,2)
|
||||
#error "Serial Port 2 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#if SERIAL_IN_USE(3)
|
||||
#if CHECK_SERIAL_PIN(TX,3)
|
||||
#error "Serial Port 3 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX,3)
|
||||
#error "Serial Port 3 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#if SERIAL_IN_USE(4)
|
||||
#if CHECK_SERIAL_PIN(TX,4)
|
||||
#error "Serial Port 4 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX,4)
|
||||
#error "Serial Port 4 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#if SERIAL_IN_USE(5)
|
||||
#if CHECK_SERIAL_PIN(TX,5)
|
||||
#error "Serial Port 5 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX,5)
|
||||
#error "Serial Port 5 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#if SERIAL_IN_USE(6)
|
||||
#if CHECK_SERIAL_PIN(TX,6)
|
||||
#error "Serial Port 6 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX,6)
|
||||
#error "Serial Port 6 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#undef CHECK_SERIAL_PIN
|
||||
#undef _CHECK_SERIAL_PIN
|
||||
|
@@ -102,17 +102,18 @@ const XrefInfo pin_xref[] PROGMEM = {
|
||||
#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
|
||||
#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
|
||||
#define PORT_NUM(P) ((P >> 4) & 0x0007)
|
||||
#define PORT_ALPHA(P) ('A' + (P >> 4))
|
||||
#define PORT_ALPHA(P) ('A' + (P >> 4))
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
*/
|
||||
|
||||
#if PA0 >= NUM_DIGITAL_PINS
|
||||
#if NUM_ANALOG_FIRST >= NUM_DIGITAL_PINS
|
||||
#define HAS_HIGH_ANALOG_PINS 1
|
||||
#endif
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS)
|
||||
#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
|
||||
#define NUM_ANALOG_LAST ((NUM_ANALOG_FIRST) + (NUM_ANALOG_INPUTS) - 1)
|
||||
#define NUMBER_PINS_TOTAL ((NUM_DIGITAL_PINS) + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS))
|
||||
#define VALID_PIN(P) (WITHIN(P, 0, (NUM_DIGITAL_PINS) - 1) || TERN0(HAS_HIGH_ANALOG_PINS, WITHIN(P, NUM_ANALOG_FIRST, NUM_ANALOG_LAST)))
|
||||
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
|
||||
#define PRINT_PIN(Q)
|
||||
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
@@ -168,7 +169,7 @@ bool GET_PINMODE(const pin_t Ard_num) {
|
||||
}
|
||||
|
||||
int8_t digital_pin_to_analog_pin(const pin_t Ard_num) {
|
||||
if (WITHIN(Ard_num, NUM_ANALOG_FIRST, NUM_ANALOG_FIRST + NUM_ANALOG_INPUTS - 1))
|
||||
if (WITHIN(Ard_num, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))
|
||||
return Ard_num - NUM_ANALOG_FIRST;
|
||||
|
||||
const uint32_t ind = digitalPinToAnalogInput(Ard_num);
|
||||
@@ -206,8 +207,11 @@ void port_print(const pin_t Ard_num) {
|
||||
SERIAL_ECHO_SP(7);
|
||||
|
||||
// Print number to be used with M42
|
||||
int calc_p = Ard_num % (NUM_DIGITAL_PINS + 1);
|
||||
if (Ard_num > NUM_DIGITAL_PINS && calc_p > 7) calc_p += 8;
|
||||
int calc_p = Ard_num;
|
||||
if (Ard_num > NUM_DIGITAL_PINS) {
|
||||
calc_p -= NUM_ANALOG_FIRST;
|
||||
if (calc_p > 7) calc_p += 8;
|
||||
}
|
||||
SERIAL_ECHOPGM(" M42 P", calc_p);
|
||||
SERIAL_CHAR(' ');
|
||||
if (calc_p < 100) {
|
||||
|
@@ -150,9 +150,9 @@ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_l
|
||||
sw_iic.start();
|
||||
sw_iic.send_byte(gt911_slave_address + 1); // Set read mode
|
||||
|
||||
LOOP_L_N(i, r_len) {
|
||||
LOOP_L_N(i, r_len)
|
||||
r_data[i] = sw_iic.read_byte(1); // Read data from reg
|
||||
}
|
||||
|
||||
sw_iic.stop();
|
||||
}
|
||||
|
||||
|
@@ -39,42 +39,18 @@ class SW_IIC {
|
||||
private:
|
||||
uint16_t scl_pin;
|
||||
uint16_t sda_pin;
|
||||
void write_scl(bool level)
|
||||
{
|
||||
WRITE(scl_pin, level);
|
||||
}
|
||||
void write_sda(bool level)
|
||||
{
|
||||
WRITE(sda_pin, level);
|
||||
}
|
||||
bool read_sda()
|
||||
{
|
||||
return READ(sda_pin);
|
||||
}
|
||||
void set_sda_out()
|
||||
{
|
||||
SET_OUTPUT(sda_pin);
|
||||
}
|
||||
void set_sda_in()
|
||||
{
|
||||
SET_INPUT_PULLUP(sda_pin);
|
||||
}
|
||||
static void iic_delay(uint8_t t)
|
||||
{
|
||||
delayMicroseconds(t);
|
||||
}
|
||||
void write_scl(bool level) { WRITE(scl_pin, level); }
|
||||
void write_sda(bool level) { WRITE(sda_pin, level); }
|
||||
bool read_sda() { return READ(sda_pin); }
|
||||
void set_sda_out() { SET_OUTPUT(sda_pin); }
|
||||
void set_sda_in() { SET_INPUT_PULLUP(sda_pin); }
|
||||
static void iic_delay(uint8_t t) { delayMicroseconds(t); }
|
||||
|
||||
public:
|
||||
SW_IIC(uint16_t sda, uint16_t scl);
|
||||
// setSCL/SDA have to be called before begin()
|
||||
void setSCL(uint16_t scl)
|
||||
{
|
||||
scl_pin = scl;
|
||||
};
|
||||
void setSDA(uint16_t sda)
|
||||
{
|
||||
sda_pin = sda;
|
||||
};
|
||||
void setSCL(uint16_t scl) { scl_pin = scl; }
|
||||
void setSDA(uint16_t sda) { sda_pin = sda; }
|
||||
void init(); // Initialize the IO port of IIC
|
||||
void start(); // Send IIC start signal
|
||||
void stop(); // Send IIC stop signal
|
||||
|
@@ -147,21 +147,36 @@ uint32_t TFT_FSMC::ReadID(tft_data_t Reg) {
|
||||
}
|
||||
|
||||
bool TFT_FSMC::isBusy() {
|
||||
#if defined(STM32F1xx)
|
||||
volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET;
|
||||
#ifdef STM32F1xx
|
||||
#define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN)
|
||||
#define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->CPAR != 0)
|
||||
#elif defined(STM32F4xx)
|
||||
volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN;
|
||||
#define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR & DMA_SxCR_EN)
|
||||
#define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->PAR != 0)
|
||||
#endif
|
||||
if (dmaEnabled) {
|
||||
if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0)
|
||||
Abort();
|
||||
}
|
||||
else
|
||||
Abort();
|
||||
return dmaEnabled;
|
||||
|
||||
if (!__IS_DMA_CONFIGURED(&DMAtx)) return false;
|
||||
|
||||
// Check if DMA transfer error or transfer complete flags are set
|
||||
if ((__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) == 0) && (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) == 0)) return true;
|
||||
|
||||
__DSB();
|
||||
Abort();
|
||||
return false;
|
||||
}
|
||||
|
||||
void TFT_FSMC::Abort() {
|
||||
HAL_DMA_Abort(&DMAtx); // Abort DMA transfer if any
|
||||
HAL_DMA_DeInit(&DMAtx); // Deconfigure DMA
|
||||
}
|
||||
|
||||
void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DMAtx.Init.PeriphInc = MemoryIncrease;
|
||||
HAL_DMA_Init(&DMAtx);
|
||||
HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(LCD->RAM), Count);
|
||||
}
|
||||
|
||||
void TFT_FSMC::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DMAtx.Init.PeriphInc = MemoryIncrease;
|
||||
HAL_DMA_Init(&DMAtx);
|
||||
DataTransferBegin();
|
||||
|
@@ -41,6 +41,7 @@
|
||||
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
|
||||
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
|
||||
#define TFT_IO_DRIVER TFT_FSMC
|
||||
#define DMA_MAX_SIZE 0xFFFF
|
||||
|
||||
#define TFT_DATASIZE TERN(TFT_INTERFACE_FSMC_8BIT, DATASIZE_8BIT, DATASIZE_16BIT)
|
||||
typedef TERN(TFT_INTERFACE_FSMC_8BIT, uint8_t, uint16_t) tft_data_t;
|
||||
@@ -59,13 +60,14 @@ class TFT_FSMC {
|
||||
|
||||
static uint32_t ReadID(tft_data_t Reg);
|
||||
static void Transmit(tft_data_t Data) { LCD->RAM = Data; __DSB(); }
|
||||
static void Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
static void Init();
|
||||
static uint32_t GetID();
|
||||
static bool isBusy();
|
||||
static void Abort() { __HAL_DMA_DISABLE(&DMAtx); }
|
||||
static void Abort();
|
||||
|
||||
static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {}
|
||||
static void DataTransferEnd() {};
|
||||
@@ -73,13 +75,14 @@ class TFT_FSMC {
|
||||
static void WriteData(uint16_t Data) { Transmit(tft_data_t(Data)); }
|
||||
static void WriteReg(uint16_t Reg) { LCD->REG = tft_data_t(Reg); __DSB(); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); }
|
||||
static void WriteSequence_DMA(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple_DMA(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
|
||||
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
@@ -356,7 +356,7 @@ void TFT_LTDC::WriteReg(uint16_t Reg) {
|
||||
reg = Reg;
|
||||
}
|
||||
|
||||
void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
void TFT_LTDC::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
|
||||
while (x_cur != x_min && Count) {
|
||||
Transmit(*Data);
|
||||
|
@@ -32,6 +32,7 @@
|
||||
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
|
||||
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
|
||||
#define TFT_IO_DRIVER TFT_LTDC
|
||||
#define DMA_MAX_SIZE 0xFFFF
|
||||
|
||||
#define TFT_DATASIZE DATASIZE_16BIT
|
||||
typedef uint16_t tft_data_t;
|
||||
@@ -49,7 +50,7 @@ class TFT_LTDC {
|
||||
static void DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color);
|
||||
static void DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors);
|
||||
static void Transmit(tft_data_t Data);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
static void Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
static void Init();
|
||||
@@ -63,13 +64,15 @@ class TFT_LTDC {
|
||||
static void WriteData(uint16_t Data);
|
||||
static void WriteReg(uint16_t Reg);
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); }
|
||||
// Non-blocking DMA data transfer is not implemented for LTDC interface
|
||||
inline static void WriteSequence_DMA(uint16_t *Data, uint16_t Count) { WriteSequence(Data, Count); }
|
||||
inline static void WriteMultiple_DMA(uint16_t Color, uint16_t Count) { WriteMultiple(Color, Count); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
|
||||
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
@@ -160,16 +160,13 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
|
||||
|
||||
for (i = 0; i < 4; i++) {
|
||||
#if TFT_MISO_PIN != TFT_MOSI_PIN
|
||||
//if (hspi->Init.Direction == SPI_DIRECTION_2LINES) {
|
||||
while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {}
|
||||
SPIx.Instance->DR = 0;
|
||||
//}
|
||||
while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {}
|
||||
SPIx.Instance->DR = 0;
|
||||
#endif
|
||||
while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_RXNE)) {}
|
||||
Data = (Data << 8) | SPIx.Instance->DR;
|
||||
}
|
||||
|
||||
__HAL_SPI_DISABLE(&SPIx);
|
||||
DataTransferEnd();
|
||||
|
||||
SPIx.Init.BaudRatePrescaler = BaudRatePrescaler;
|
||||
@@ -179,36 +176,44 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
|
||||
}
|
||||
|
||||
bool TFT_SPI::isBusy() {
|
||||
#if defined(STM32F1xx)
|
||||
volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET;
|
||||
#ifdef STM32F1xx
|
||||
#define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CCR & DMA_CCR_EN)
|
||||
#define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->CPAR != 0)
|
||||
#elif defined(STM32F4xx)
|
||||
volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN;
|
||||
#define __IS_DMA_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR & DMA_SxCR_EN)
|
||||
#define __IS_DMA_CONFIGURED(__HANDLE__) ((__HANDLE__)->Instance->PAR != 0)
|
||||
#endif
|
||||
if (dmaEnabled) {
|
||||
if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0)
|
||||
Abort();
|
||||
|
||||
if (!__IS_DMA_CONFIGURED(&DMAtx)) return false;
|
||||
|
||||
if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx))) {
|
||||
// You should not be here - DMA transfer error flag is set
|
||||
// Abort DMA transfer and release SPI
|
||||
}
|
||||
else
|
||||
Abort();
|
||||
return dmaEnabled;
|
||||
else {
|
||||
// Check if DMA transfer completed flag is set
|
||||
if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) == 0) return true;
|
||||
// Check if SPI transmit butter is empty and SPI is idle
|
||||
if ((!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) || (__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY))) return true;
|
||||
}
|
||||
|
||||
Abort();
|
||||
return false;
|
||||
}
|
||||
|
||||
void TFT_SPI::Abort() {
|
||||
// Wait for any running spi
|
||||
while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {}
|
||||
while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {}
|
||||
// First, abort any running dma
|
||||
HAL_DMA_Abort(&DMAtx);
|
||||
// DeInit objects
|
||||
HAL_DMA_Abort(&DMAtx); // Abort DMA transfer if any
|
||||
HAL_DMA_DeInit(&DMAtx);
|
||||
HAL_SPI_DeInit(&SPIx);
|
||||
// Deselect CS
|
||||
DataTransferEnd();
|
||||
|
||||
CLEAR_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN);
|
||||
|
||||
DataTransferEnd(); // Stop SPI and deselect CS
|
||||
}
|
||||
|
||||
void TFT_SPI::Transmit(uint16_t Data) {
|
||||
if (TFT_MISO_PIN == TFT_MOSI_PIN)
|
||||
#if TFT_MISO_PIN == TFT_MOSI_PIN
|
||||
SPI_1LINE_TX(&SPIx);
|
||||
#endif
|
||||
|
||||
__HAL_SPI_ENABLE(&SPIx);
|
||||
|
||||
@@ -217,14 +222,31 @@ void TFT_SPI::Transmit(uint16_t Data) {
|
||||
while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {}
|
||||
while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {}
|
||||
|
||||
if (TFT_MISO_PIN != TFT_MOSI_PIN)
|
||||
__HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read
|
||||
#if TFT_MISO_PIN != TFT_MOSI_PIN
|
||||
__HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received data is not read
|
||||
#endif
|
||||
}
|
||||
|
||||
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
// Wait last dma finish, to start another
|
||||
while (isBusy()) { /* nada */ }
|
||||
DMAtx.Init.MemInc = MemoryIncrease;
|
||||
HAL_DMA_Init(&DMAtx);
|
||||
|
||||
#if TFT_MISO_PIN == TFT_MOSI_PIN
|
||||
SPI_1LINE_TX(&SPIx);
|
||||
#endif
|
||||
|
||||
DataTransferBegin();
|
||||
|
||||
HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count);
|
||||
__HAL_SPI_ENABLE(&SPIx);
|
||||
|
||||
SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request
|
||||
|
||||
TERN_(TFT_SHARED_SPI, while (isBusy()));
|
||||
}
|
||||
|
||||
|
||||
void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DMAtx.Init.MemInc = MemoryIncrease;
|
||||
HAL_DMA_Init(&DMAtx);
|
||||
|
||||
@@ -243,7 +265,6 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun
|
||||
}
|
||||
|
||||
#if ENABLED(USE_SPI_DMA_TC)
|
||||
|
||||
void TFT_SPI::TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
|
||||
DMAtx.Init.MemInc = MemoryIncrease;
|
||||
@@ -262,8 +283,7 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun
|
||||
SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request
|
||||
}
|
||||
|
||||
extern "C" void DMA2_Stream3_IRQHandler(void) { HAL_DMA_IRQHandler(&TFT_SPI::DMAtx); }
|
||||
|
||||
extern "C" void DMA2_Stream3_IRQHandler(void) { TFT_SPI::DMA_IRQHandler(); }
|
||||
#endif
|
||||
|
||||
#endif // HAS_SPI_TFT
|
||||
|
@@ -39,46 +39,47 @@
|
||||
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
|
||||
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
|
||||
#define TFT_IO_DRIVER TFT_SPI
|
||||
#define DMA_MAX_SIZE 0xFFFF
|
||||
|
||||
class TFT_SPI {
|
||||
private:
|
||||
static SPI_HandleTypeDef SPIx;
|
||||
|
||||
static DMA_HandleTypeDef DMAtx;
|
||||
|
||||
static uint32_t ReadID(uint16_t Reg);
|
||||
static void Transmit(uint16_t Data);
|
||||
static void Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
#if ENABLED(USE_SPI_DMA_TC)
|
||||
static void TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
#endif
|
||||
|
||||
public:
|
||||
static DMA_HandleTypeDef DMAtx;
|
||||
|
||||
static void Init();
|
||||
static uint32_t GetID();
|
||||
static bool isBusy();
|
||||
static void Abort();
|
||||
|
||||
static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT);
|
||||
static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); };
|
||||
static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); __HAL_SPI_DISABLE(&SPIx); };
|
||||
static void DataTransferAbort();
|
||||
|
||||
static void WriteData(uint16_t Data) { Transmit(Data); }
|
||||
static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteSequence_DMA(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple_DMA(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
|
||||
#if ENABLED(USE_SPI_DMA_TC)
|
||||
static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { TransmitDMA_IT(DMA_MINC_ENABLE, Data, Count); }
|
||||
inline static void DMA_IRQHandler() { HAL_DMA_IRQHandler(&TFT_SPI::DMAtx); }
|
||||
#endif
|
||||
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
|
||||
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
@@ -526,23 +526,22 @@ void SPIClass::onReceive(void(*callback)()) {
|
||||
_currentSetting->receiveCallback = callback;
|
||||
if (callback) {
|
||||
switch (_currentSetting->spi_d->clk_id) {
|
||||
#if BOARD_NR_SPI >= 1
|
||||
case RCC_SPI1:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 2
|
||||
case RCC_SPI2:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 3
|
||||
case RCC_SPI3:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
ASSERT(0);
|
||||
#if BOARD_NR_SPI >= 1
|
||||
case RCC_SPI1:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 2
|
||||
case RCC_SPI2:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 3
|
||||
case RCC_SPI3:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback);
|
||||
break;
|
||||
#endif
|
||||
default: ASSERT(0);
|
||||
}
|
||||
}
|
||||
else {
|
||||
@@ -554,23 +553,22 @@ void SPIClass::onTransmit(void(*callback)()) {
|
||||
_currentSetting->transmitCallback = callback;
|
||||
if (callback) {
|
||||
switch (_currentSetting->spi_d->clk_id) {
|
||||
#if BOARD_NR_SPI >= 1
|
||||
case RCC_SPI1:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 2
|
||||
case RCC_SPI2:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 3
|
||||
case RCC_SPI3:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
ASSERT(0);
|
||||
#if BOARD_NR_SPI >= 1
|
||||
case RCC_SPI1:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 2
|
||||
case RCC_SPI2:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback);
|
||||
break;
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 3
|
||||
case RCC_SPI3:
|
||||
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback);
|
||||
break;
|
||||
#endif
|
||||
default: ASSERT(0);
|
||||
}
|
||||
}
|
||||
else {
|
||||
|
@@ -33,6 +33,15 @@
|
||||
#include <stdint.h>
|
||||
#include <wirish.h>
|
||||
|
||||
// Number of SPI ports
|
||||
#ifdef BOARD_SPI3_SCK_PIN
|
||||
#define BOARD_NR_SPI 3
|
||||
#elif defined(BOARD_SPI2_SCK_PIN)
|
||||
#define BOARD_NR_SPI 2
|
||||
#elif defined(BOARD_SPI1_SCK_PIN)
|
||||
#define BOARD_NR_SPI 1
|
||||
#endif
|
||||
|
||||
// SPI_HAS_TRANSACTION means SPI has
|
||||
// - beginTransaction()
|
||||
// - endTransaction()
|
||||
|
@@ -215,22 +215,47 @@ uint32_t TFT_FSMC::GetID() {
|
||||
}
|
||||
|
||||
bool TFT_FSMC::isBusy() {
|
||||
#define __IS_DMA_CONFIGURED(__DMAx__, __CHx__) (dma_channel_regs(__DMAx__, __CHx__)->CPAR != 0)
|
||||
|
||||
if (!__IS_DMA_CONFIGURED(FSMC_DMA_DEV, FSMC_DMA_CHANNEL)) return false;
|
||||
|
||||
// Check if DMA transfer error or transfer complete flags are set
|
||||
if ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & (DMA_ISR_TCIF | DMA_ISR_TEIF)) == 0) return true;
|
||||
|
||||
__DSB();
|
||||
Abort();
|
||||
return false;
|
||||
}
|
||||
|
||||
void TFT_FSMC::Abort() {
|
||||
dma_channel_reg_map *channel_regs = dma_channel_regs(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||
|
||||
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); // Abort DMA transfer if any
|
||||
|
||||
// Deconfigure DMA
|
||||
channel_regs->CCR = 0U;
|
||||
channel_regs->CNDTR = 0U;
|
||||
channel_regs->CMAR = 0U;
|
||||
channel_regs->CPAR = 0U;
|
||||
}
|
||||
|
||||
void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
// TODO: HAL STM32 uses DMA2_Channel1 for FSMC on STM32F1
|
||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | MemoryIncrease);
|
||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Count);
|
||||
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||
}
|
||||
|
||||
void TFT_FSMC::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
#if defined(FSMC_DMA_DEV) && defined(FSMC_DMA_CHANNEL)
|
||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | MemoryIncrease);
|
||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Count);
|
||||
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||
|
||||
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {};
|
||||
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & (DMA_CCR_TEIE | DMA_CCR_TCIE)) == 0) {}
|
||||
Abort();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -33,6 +33,10 @@
|
||||
#define DATASIZE_8BIT DMA_SIZE_8BITS
|
||||
#define DATASIZE_16BIT DMA_SIZE_16BITS
|
||||
#define TFT_IO_DRIVER TFT_FSMC
|
||||
#define DMA_MAX_SIZE 0xFFFF
|
||||
|
||||
#define DMA_PINC_ENABLE DMA_PINC_MODE
|
||||
#define DMA_PINC_DISABLE 0
|
||||
|
||||
typedef struct {
|
||||
__IO uint16_t REG;
|
||||
@@ -45,6 +49,7 @@ class TFT_FSMC {
|
||||
|
||||
static uint32_t ReadID(uint16_t Reg);
|
||||
static void Transmit(uint16_t Data);
|
||||
static void Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
@@ -59,13 +64,14 @@ class TFT_FSMC {
|
||||
static void WriteData(uint16_t Data) { Transmit(Data); }
|
||||
static void WriteReg(uint16_t Reg);
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); }
|
||||
static void WriteSequence_DMA(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple_DMA(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_CIRC_MODE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
|
||||
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
@@ -26,7 +26,7 @@
|
||||
|
||||
#include "tft_spi.h"
|
||||
|
||||
SPIClass TFT_SPI::SPIx(1);
|
||||
SPIClass TFT_SPI::SPIx(TFT_SPI_DEVICE);
|
||||
|
||||
void TFT_SPI::Init() {
|
||||
#if PIN_EXISTS(TFT_RESET)
|
||||
@@ -46,7 +46,7 @@ void TFT_SPI::Init() {
|
||||
* STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1
|
||||
* so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2
|
||||
*/
|
||||
#if SPI_DEVICE == 1
|
||||
#if TFT_SPI_DEVICE == 1
|
||||
#define SPI_CLOCK_MAX SPI_CLOCK_DIV4
|
||||
#else
|
||||
#define SPI_CLOCK_MAX SPI_CLOCK_DIV2
|
||||
@@ -62,7 +62,7 @@ void TFT_SPI::Init() {
|
||||
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
|
||||
default: clock = SPI_CLOCK_DIV2; // Default from the SPI library
|
||||
}
|
||||
SPIx.setModule(1);
|
||||
SPIx.setModule(TFT_SPI_DEVICE);
|
||||
SPIx.setClockDivider(clock);
|
||||
SPIx.setBitOrder(MSBFIRST);
|
||||
SPIx.setDataMode(SPI_MODE0);
|
||||
@@ -71,7 +71,7 @@ void TFT_SPI::Init() {
|
||||
void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
|
||||
SPIx.setDataSize(DataSize);
|
||||
SPIx.begin();
|
||||
OUT_WRITE(TFT_CS_PIN, LOW);
|
||||
WRITE(TFT_CS_PIN, LOW);
|
||||
}
|
||||
|
||||
#ifdef TFT_DEFAULT_DRIVER
|
||||
@@ -113,15 +113,53 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
|
||||
#endif
|
||||
}
|
||||
|
||||
bool TFT_SPI::isBusy() { return false; }
|
||||
bool TFT_SPI::isBusy() {
|
||||
#define __IS_DMA_CONFIGURED(__DMAx__, __CHx__) (dma_channel_regs(__DMAx__, __CHx__)->CPAR != 0)
|
||||
|
||||
void TFT_SPI::Abort() { DataTransferEnd(); }
|
||||
if (!__IS_DMA_CONFIGURED(DMAx, DMA_CHx)) return false;
|
||||
|
||||
if (dma_get_isr_bits(DMAx, DMA_CHx) & DMA_ISR_TEIF) {
|
||||
// You should not be here - DMA transfer error flag is set
|
||||
// Abort DMA transfer and release SPI
|
||||
}
|
||||
else {
|
||||
// Check if DMA transfer completed flag is set
|
||||
if (!(dma_get_isr_bits(DMAx, DMA_CHx) & DMA_ISR_TCIF)) return true;
|
||||
// Check if SPI TX butter is empty and SPI is idle
|
||||
if (!(SPIdev->regs->SR & SPI_SR_TXE) || (SPIdev->regs->SR & SPI_SR_BSY)) return true;
|
||||
}
|
||||
|
||||
Abort();
|
||||
return false;
|
||||
}
|
||||
|
||||
void TFT_SPI::Abort() {
|
||||
dma_channel_reg_map *channel_regs = dma_channel_regs(DMAx, DMA_CHx);
|
||||
|
||||
dma_disable(DMAx, DMA_CHx); // Abort DMA transfer if any
|
||||
spi_tx_dma_disable(SPIdev);
|
||||
|
||||
// Deconfigure DMA
|
||||
channel_regs->CCR = 0U;
|
||||
channel_regs->CNDTR = 0U;
|
||||
channel_regs->CMAR = 0U;
|
||||
channel_regs->CPAR = 0U;
|
||||
|
||||
DataTransferEnd();
|
||||
}
|
||||
|
||||
void TFT_SPI::Transmit(uint16_t Data) { SPIx.send(Data); }
|
||||
|
||||
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DataTransferBegin();
|
||||
OUT_WRITE(TFT_DC_PIN, HIGH);
|
||||
SPIx.dmaSendAsync(Data, Count, MemoryIncrease == DMA_MINC_ENABLE);
|
||||
|
||||
TERN_(TFT_SHARED_SPI, while (isBusy()));
|
||||
}
|
||||
|
||||
void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
WRITE(TFT_DC_PIN, HIGH);
|
||||
DataTransferBegin();
|
||||
SPIx.dmaSend(Data, Count, MemoryIncrease == DMA_MINC_ENABLE);
|
||||
DataTransferEnd();
|
||||
}
|
||||
|
@@ -25,6 +25,27 @@
|
||||
|
||||
#include <SPI.h>
|
||||
|
||||
#define IS_SPI(N) (BOARD_NR_SPI >= N && (TFT_SCK_PIN == BOARD_SPI##N##_SCK_PIN) && (TFT_MOSI_PIN == BOARD_SPI##N##_MOSI_PIN) && (TFT_MISO_PIN == BOARD_SPI##N##_MISO_PIN))
|
||||
#if IS_SPI(1)
|
||||
#define TFT_SPI_DEVICE 1
|
||||
#define SPIdev SPI1
|
||||
#define DMAx DMA1
|
||||
#define DMA_CHx DMA_CH3
|
||||
#elif IS_SPI(2)
|
||||
#define TFT_SPI_DEVICE 2
|
||||
#define SPIdev SPI2
|
||||
#define DMAx DMA1
|
||||
#define DMA_CHx DMA_CH5
|
||||
#elif IS_SPI(3)
|
||||
#define TFT_SPI_DEVICE 3
|
||||
#define SPIdev SPI3
|
||||
#define DMAx DMA2
|
||||
#define DMA_CHx DMA_CH2
|
||||
#else
|
||||
#error "Invalid TFT SPI configuration."
|
||||
#endif
|
||||
#undef IS_SPI
|
||||
|
||||
#ifndef LCD_READ_ID
|
||||
#define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
@@ -32,17 +53,19 @@
|
||||
#define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
|
||||
#define DATASIZE_8BIT DATA_SIZE_8BIT
|
||||
#define DATASIZE_16BIT DATA_SIZE_16BIT
|
||||
#define TFT_IO_DRIVER TFT_SPI
|
||||
#define DATASIZE_8BIT DATA_SIZE_8BIT
|
||||
#define DATASIZE_16BIT DATA_SIZE_16BIT
|
||||
#define TFT_IO_DRIVER TFT_SPI
|
||||
#define DMA_MAX_SIZE 0xFFFF
|
||||
|
||||
#define DMA_MINC_ENABLE 1
|
||||
#define DMA_MINC_DISABLE 0
|
||||
#define DMA_MINC_ENABLE DMA_MINC_MODE
|
||||
#define DMA_MINC_DISABLE 0
|
||||
|
||||
class TFT_SPI {
|
||||
private:
|
||||
static uint32_t ReadID(uint16_t Reg);
|
||||
static void Transmit(uint16_t Data);
|
||||
static void Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
@@ -58,15 +81,16 @@ public:
|
||||
static void DataTransferAbort();
|
||||
|
||||
static void WriteData(uint16_t Data) { Transmit(Data); }
|
||||
static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); }
|
||||
static void WriteReg(uint16_t Reg) { WRITE(TFT_DC_PIN, LOW); Transmit(Reg); WRITE(TFT_DC_PIN, HIGH); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
static void WriteSequence_DMA(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple_DMA(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count);
|
||||
Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
@@ -36,7 +36,7 @@
|
||||
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define GET_ARRAY_PIN(p) pin_array[p].pin
|
||||
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0)
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
|
||||
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0))
|
||||
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(13)) || ((P) >= analogInputToDigitalPin(14) && (P) <= analogInputToDigitalPin(17))
|
||||
#define pwm_status(pin) HAL_pwm_status(pin)
|
||||
|
@@ -50,6 +50,8 @@
|
||||
#define HAL_PATH(PATH, NAME) XSTR(PATH/NATIVE_SIM/NAME)
|
||||
#elif defined(__SAMD51__)
|
||||
#define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME)
|
||||
#elif defined(__SAMD21__)
|
||||
#define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD21/NAME)
|
||||
#else
|
||||
#error "Unsupported Platform!"
|
||||
#endif
|
||||
|
@@ -33,8 +33,9 @@
|
||||
void UnwPrintf(const char *format, ...) {
|
||||
va_list args;
|
||||
|
||||
va_start( args, format );
|
||||
vprintf(format, args );
|
||||
va_start(args, format);
|
||||
vprintf(format, args);
|
||||
va_end(args);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@@ -83,10 +83,10 @@
|
||||
#else
|
||||
#include <stdint.h>
|
||||
|
||||
#if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__)
|
||||
#if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__)
|
||||
// we're good to go
|
||||
#else
|
||||
#error "This library only supports boards with an AVR, SAM3X or SAMD51 processor."
|
||||
#error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor."
|
||||
#endif
|
||||
|
||||
#define Servo_VERSION 2 // software version of this library
|
||||
|
@@ -49,8 +49,10 @@
|
||||
#include "../DUE/ServoTimers.h"
|
||||
#elif defined(__SAMD51__)
|
||||
#include "../SAMD51/ServoTimers.h"
|
||||
#elif defined(__SAMD21__)
|
||||
#include "../SAMD21/ServoTimers.h"
|
||||
#else
|
||||
#error "This library only supports boards with an AVR, SAM3X or SAMD51 processor."
|
||||
#error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor."
|
||||
#endif
|
||||
|
||||
// Macros
|
||||
|
@@ -353,7 +353,7 @@ void startOrResumeJob() {
|
||||
TERN_(GCODE_REPEAT_MARKERS, repeat.reset());
|
||||
TERN_(CANCEL_OBJECTS, cancelable.reset());
|
||||
TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0);
|
||||
#if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME)
|
||||
#if ENABLED(SET_REMAINING_TIME)
|
||||
ui.reset_remaining_time();
|
||||
#endif
|
||||
}
|
||||
@@ -582,7 +582,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAS_FREEZE_PIN
|
||||
#if ENABLED(FREEZE_FEATURE)
|
||||
stepper.frozen = READ(FREEZE_PIN) == FREEZE_STATE;
|
||||
#endif
|
||||
|
||||
|
@@ -110,15 +110,16 @@
|
||||
#define BOARD_COPYMASTER_3D 1154 // Copymaster 3D
|
||||
#define BOARD_ORTUR_4 1155 // Ortur 4
|
||||
#define BOARD_TENLOG_D3_HERO 1156 // Tenlog D3 Hero IDEX printer
|
||||
#define BOARD_RAMPS_S_12_EEFB 1157 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed)
|
||||
#define BOARD_RAMPS_S_12_EEEB 1158 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed)
|
||||
#define BOARD_RAMPS_S_12_EFFB 1159 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed)
|
||||
#define BOARD_LONGER3D_LK1_PRO 1160 // Longer LK1 PRO / Alfawise U20 Pro (PRO version)
|
||||
#define BOARD_LONGER3D_LKx_PRO 1161 // Longer LKx PRO / Alfawise Uxx Pro (PRO version)
|
||||
#define BOARD_ZRIB_V53 1162 // Zonestar zrib V5.3 (Chinese RAMPS replica)
|
||||
#define BOARD_PXMALION_CORE_I3 1163 // Pxmalion Core I3
|
||||
#define BOARD_TENLOG_MB1_V23 1157 // Tenlog D3, D5, D6 IDEX Printer
|
||||
#define BOARD_RAMPS_S_12_EEFB 1158 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed)
|
||||
#define BOARD_RAMPS_S_12_EEEB 1159 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed)
|
||||
#define BOARD_RAMPS_S_12_EFFB 1160 // Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed)
|
||||
#define BOARD_LONGER3D_LK1_PRO 1161 // Longer LK1 PRO / Alfawise U20 Pro (PRO version)
|
||||
#define BOARD_LONGER3D_LKx_PRO 1162 // Longer LKx PRO / Alfawise Uxx Pro (PRO version)
|
||||
#define BOARD_ZRIB_V53 1163 // Zonestar zrib V5.3 (Chinese RAMPS replica)
|
||||
#define BOARD_PXMALION_CORE_I3 1164 // Pxmalion Core I3
|
||||
// PATCH START: Knutwurst
|
||||
#define BOARD_TRIGORILLA_CHIRON 1164 // TriGorilla Anycubic version 1.4 based on RAMPS EFB for Chiron
|
||||
#define BOARD_TRIGORILLA_CHIRON 1165 // TriGorilla Anycubic version 1.4 based on RAMPS EFB for Chiron
|
||||
// PATCH END: Knutwurst
|
||||
|
||||
//
|
||||
@@ -327,50 +328,53 @@
|
||||
#define BOARD_MKS_ROBIN_E3D 4020 // MKS Robin E3D (STM32F103RC)
|
||||
#define BOARD_MKS_ROBIN_E3D_V1_1 4021 // MKS Robin E3D V1.1 (STM32F103RC)
|
||||
#define BOARD_MKS_ROBIN_E3P 4022 // MKS Robin E3p (STM32F103VE)
|
||||
#define BOARD_BTT_SKR_MINI_V1_1 4023 // BigTreeTech SKR Mini v1.1 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V3_0 4027 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RE)
|
||||
#define BOARD_BTT_SKR_MINI_MZ_V1_0 4028 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_E3_DIP 4029 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_BTT_SKR_CR6 4030 // BigTreeTech SKR CR6 v1.0 (STM32F103RE)
|
||||
#define BOARD_JGAURORA_A5S_A1 4031 // JGAurora A5S A1 (STM32F103ZE)
|
||||
#define BOARD_FYSETC_AIO_II 4032 // FYSETC AIO_II (STM32F103RC)
|
||||
#define BOARD_FYSETC_CHEETAH 4033 // FYSETC Cheetah (STM32F103RC)
|
||||
#define BOARD_FYSETC_CHEETAH_V12 4034 // FYSETC Cheetah V1.2 (STM32F103RC)
|
||||
#define BOARD_LONGER3D_LK 4035 // Longer3D LK1/2 - Alfawise U20/U20+/U30 (STM32F103VE)
|
||||
#define BOARD_CCROBOT_MEEB_3DP 4036 // ccrobot-online.com MEEB_3DP (STM32F103RC)
|
||||
#define BOARD_CHITU3D_V5 4037 // Chitu3D TronXY X5SA V5 Board (STM32F103ZE)
|
||||
#define BOARD_CHITU3D_V6 4038 // Chitu3D TronXY X5SA V6 Board (STM32F103ZE)
|
||||
#define BOARD_CHITU3D_V9 4039 // Chitu3D TronXY X5SA V9 Board (STM32F103ZE)
|
||||
#define BOARD_CREALITY_V4 4040 // Creality v4.x (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V422 4041 // Creality v4.2.2 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V423 4042 // Creality v4.2.3 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V425 4043 // Creality v4.2.5 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V427 4044 // Creality v4.2.7 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V4210 4045 // Creality v4.2.10 (STM32F103RC / STM32F103RE) as found in the CR-30
|
||||
#define BOARD_CREALITY_V431 4046 // Creality v4.3.1 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_A 4047 // Creality v4.3.1a (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_B 4048 // Creality v4.3.1b (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_C 4049 // Creality v4.3.1c (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_D 4050 // Creality v4.3.1d (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V452 4051 // Creality v4.5.2 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V453 4052 // Creality v4.5.3 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V24S1 4053 // Creality v2.4.S1 (STM32F103RC / STM32F103RE) v101 as found in the Ender-7
|
||||
#define BOARD_CREALITY_V24S1_301 4054 // Creality v2.4.S1_301 (STM32F103RC / STM32F103RE) v301 as found in the Ender-3 S1
|
||||
#define BOARD_CREALITY_V25S1 4055 // Creality v2.5.S1 (STM32F103RE) as found in the CR-10 Smart Pro
|
||||
#define BOARD_TRIGORILLA_PRO 4056 // Trigorilla Pro (STM32F103ZE)
|
||||
#define BOARD_FLY_MINI 4057 // FLYmaker FLY MINI (STM32F103RC)
|
||||
#define BOARD_FLSUN_HISPEED 4058 // FLSUN HiSpeedV1 (STM32F103VE)
|
||||
#define BOARD_BEAST 4059 // STM32F103RE Libmaple-based controller
|
||||
#define BOARD_MINGDA_MPX_ARM_MINI 4060 // STM32F103ZE Mingda MD-16
|
||||
#define BOARD_GTM32_PRO_VD 4061 // STM32F103VE controller
|
||||
#define BOARD_ZONESTAR_ZM3E2 4062 // Zonestar ZM3E2 (STM32F103RC)
|
||||
#define BOARD_ZONESTAR_ZM3E4 4063 // Zonestar ZM3E4 V1 (STM32F103VC)
|
||||
#define BOARD_ZONESTAR_ZM3E4V2 4064 // Zonestar ZM3E4 V2 (STM32F103VC)
|
||||
#define BOARD_ERYONE_ERY32_MINI 4065 // Eryone Ery32 mini (STM32F103VE)
|
||||
#define BOARD_PANDA_PI_V29 4066 // Panda Pi V2.9 - Standalone (STM32F103RC)
|
||||
#define BOARD_BTT_EBB42_V1_1 4023 // BigTreeTech EBB42 V1.1 (STM32G0B1CB)
|
||||
#define BOARD_BTT_SKR_MINI_V1_1 4024 // BigTreeTech SKR Mini v1.1 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V1_0 4025 // BigTreeTech SKR Mini E3 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V1_2 4026 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V2_0 4027 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V3_0 4028 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RE)
|
||||
#define BOARD_BTT_SKR_MINI_E3_V3_0_1 4029 // BigTreeTech SKR Mini E3 V3.0.1 (STM32F401RC)
|
||||
#define BOARD_BTT_SKR_MINI_MZ_V1_0 4030 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC)
|
||||
#define BOARD_BTT_SKR_E3_DIP 4031 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_BTT_SKR_CR6 4032 // BigTreeTech SKR CR6 v1.0 (STM32F103RE)
|
||||
#define BOARD_JGAURORA_A5S_A1 4033 // JGAurora A5S A1 (STM32F103ZE)
|
||||
#define BOARD_FYSETC_AIO_II 4034 // FYSETC AIO_II (STM32F103RC)
|
||||
#define BOARD_FYSETC_CHEETAH 4035 // FYSETC Cheetah (STM32F103RC)
|
||||
#define BOARD_FYSETC_CHEETAH_V12 4036 // FYSETC Cheetah V1.2 (STM32F103RC)
|
||||
#define BOARD_LONGER3D_LK 4037 // Longer3D LK1/2 - Alfawise U20/U20+/U30 (STM32F103VE)
|
||||
#define BOARD_CCROBOT_MEEB_3DP 4038 // ccrobot-online.com MEEB_3DP (STM32F103RC)
|
||||
#define BOARD_CHITU3D_V5 4039 // Chitu3D TronXY X5SA V5 Board (STM32F103ZE)
|
||||
#define BOARD_CHITU3D_V6 4040 // Chitu3D TronXY X5SA V6 Board (STM32F103ZE)
|
||||
#define BOARD_CHITU3D_V9 4041 // Chitu3D TronXY X5SA V9 Board (STM32F103ZE)
|
||||
#define BOARD_CREALITY_V4 4042 // Creality v4.x (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V422 4043 // Creality v4.2.2 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V423 4044 // Creality v4.2.3 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V425 4045 // Creality v4.2.5 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V427 4046 // Creality v4.2.7 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V4210 4047 // Creality v4.2.10 (STM32F103RC / STM32F103RE) as found in the CR-30
|
||||
#define BOARD_CREALITY_V431 4048 // Creality v4.3.1 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_A 4049 // Creality v4.3.1a (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_B 4050 // Creality v4.3.1b (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_C 4051 // Creality v4.3.1c (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V431_D 4052 // Creality v4.3.1d (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V452 4053 // Creality v4.5.2 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V453 4054 // Creality v4.5.3 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V521 4055 // Creality v5.2.1 (STM32F103VE) as found in the SV04
|
||||
#define BOARD_CREALITY_V24S1 4056 // Creality v2.4.S1 (STM32F103RC / STM32F103RE) v101 as found in the Ender-7
|
||||
#define BOARD_CREALITY_V24S1_301 4057 // Creality v2.4.S1_301 (STM32F103RC / STM32F103RE) v301 as found in the Ender-3 S1
|
||||
#define BOARD_CREALITY_V25S1 4058 // Creality v2.5.S1 (STM32F103RE) as found in the CR-10 Smart Pro
|
||||
#define BOARD_TRIGORILLA_PRO 4059 // Trigorilla Pro (STM32F103ZE)
|
||||
#define BOARD_FLY_MINI 4060 // FLYmaker FLY MINI (STM32F103RC)
|
||||
#define BOARD_FLSUN_HISPEED 4061 // FLSUN HiSpeedV1 (STM32F103VE)
|
||||
#define BOARD_BEAST 4062 // STM32F103RE Libmaple-based controller
|
||||
#define BOARD_MINGDA_MPX_ARM_MINI 4063 // STM32F103ZE Mingda MD-16
|
||||
#define BOARD_GTM32_PRO_VD 4064 // STM32F103VE controller
|
||||
#define BOARD_ZONESTAR_ZM3E2 4065 // Zonestar ZM3E2 (STM32F103RC)
|
||||
#define BOARD_ZONESTAR_ZM3E4 4066 // Zonestar ZM3E4 V1 (STM32F103VC)
|
||||
#define BOARD_ZONESTAR_ZM3E4V2 4067 // Zonestar ZM3E4 V2 (STM32F103VC)
|
||||
#define BOARD_ERYONE_ERY32_MINI 4068 // Eryone Ery32 mini (STM32F103VE)
|
||||
#define BOARD_PANDA_PI_V29 4069 // Panda Pi V2.9 - Standalone (STM32F103RC)
|
||||
|
||||
//
|
||||
// ARM Cortex-M4F
|
||||
@@ -424,6 +428,10 @@
|
||||
#define BOARD_ARTILLERY_RUBY 4238 // Artillery Ruby (STM32F401RC)
|
||||
#define BOARD_FYSETC_SPIDER_V2_2 4239 // FYSETC Spider V2.2 (STM32F446VE)
|
||||
#define BOARD_CREALITY_V24S1_301F4 4240 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4
|
||||
#define BOARD_OPULO_LUMEN_REV4 4241 // Opulo Lumen PnP Controller REV4 (STM32F407VE / STM32F407VG)
|
||||
#define BOARD_FYSETC_SPIDER_KING407 4242 // FYSETC Spider King407 (STM32F407ZG)
|
||||
#define BOARD_MKS_SKIPR_V1 4243 // MKS SKIPR v1.0 all-in-one board (STM32F407VE)
|
||||
#define BOARD_TRONXY_V10 4244 // TRONXY V10 (STM32F446ZE)
|
||||
|
||||
//
|
||||
// ARM Cortex M7
|
||||
@@ -461,6 +469,12 @@
|
||||
#define BOARD_BRICOLEMON_V1_0 6101 // Bricolemon
|
||||
#define BOARD_BRICOLEMON_LITE_V1_0 6102 // Bricolemon Lite
|
||||
|
||||
//
|
||||
// SAMD21 ARM Cortex M4
|
||||
//
|
||||
|
||||
#define BOARD_MINITRONICS20 6103 // Minitronics v2.0
|
||||
|
||||
//
|
||||
// Custom board
|
||||
//
|
||||
|
@@ -125,6 +125,8 @@
|
||||
|| AXIS_DRIVER_TYPE(A,TMC2660) \
|
||||
|| AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) )
|
||||
|
||||
#define AXIS_IS_TMC_CONFIG(A) ( AXIS_IS_TMC(A) || AXIS_DRIVER_TYPE(A,TMC26X) )
|
||||
|
||||
// Test for a driver that uses SPI - this allows checking whether a _CS_ pin
|
||||
// is considered sensitive
|
||||
#define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \
|
||||
|
@@ -174,6 +174,7 @@
|
||||
#define STR_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
#define STR_SD_OPENROOT_FAIL "openRoot failed"
|
||||
#define STR_SD_CARD_OK "SD card ok"
|
||||
#define STR_SD_CARD_RELEASED "SD card released"
|
||||
#define STR_SD_WORKDIR_FAIL "workDir open failed"
|
||||
#define STR_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
#define STR_SD_FILE_OPENED "File opened: "
|
||||
|
@@ -21,7 +21,7 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#if !defined(__has_include)
|
||||
#ifndef __has_include
|
||||
#define __has_include(...) 1
|
||||
#endif
|
||||
|
||||
@@ -338,6 +338,12 @@
|
||||
#define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K)
|
||||
|
||||
// Macros for initializing arrays
|
||||
#define LIST_26(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z
|
||||
#define LIST_25(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y
|
||||
#define LIST_24(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X
|
||||
#define LIST_23(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W
|
||||
#define LIST_22(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V
|
||||
#define LIST_21(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U
|
||||
#define LIST_20(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T
|
||||
#define LIST_19(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S
|
||||
#define LIST_18(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R
|
||||
@@ -732,6 +738,7 @@
|
||||
#define MAPLIST(OP,V...) EVAL(_MAPLIST(OP,V))
|
||||
|
||||
// Temperature Sensor Config
|
||||
#define _HAS_E_TEMP(N) || (TEMP_SENSOR_##N != 0)
|
||||
#define TEMP_SENSOR(N) TEMP_SENSOR_##N
|
||||
#define _HAS_E_TEMP(N) || TEMP_SENSOR(N)
|
||||
#define HAS_E_TEMP_SENSOR (0 REPEAT(EXTRUDERS, _HAS_E_TEMP))
|
||||
#define TEMP_SENSOR_IS_MAX_TC(T) (TEMP_SENSOR_##T == -5 || TEMP_SENSOR_##T == -3 || TEMP_SENSOR_##T == -2)
|
||||
#define TEMP_SENSOR_IS_MAX_TC(T) (TEMP_SENSOR(T) == -5 || TEMP_SENSOR(T) == -3 || TEMP_SENSOR(T) == -2)
|
||||
|
@@ -36,6 +36,8 @@ struct IF { typedef R type; };
|
||||
template <class L, class R>
|
||||
struct IF<true, L, R> { typedef L type; };
|
||||
|
||||
#define ALL_AXIS_NAMES X, X2, Y, Y2, Z, Z2, Z3, Z4, I, J, K, U, V, W, E0, E1, E2, E3, E4, E5, E6, E7
|
||||
|
||||
#define NUM_AXIS_GANG(V...) GANG_N(NUM_AXES, V)
|
||||
#define NUM_AXIS_CODE(V...) CODE_N(NUM_AXES, V)
|
||||
#define NUM_AXIS_LIST(V...) LIST_N(NUM_AXES, V)
|
||||
@@ -99,8 +101,8 @@ struct Flags {
|
||||
void set(const int n) { b |= (bits_t)_BV(n); }
|
||||
void clear(const int n) { b &= ~(bits_t)_BV(n); }
|
||||
bool test(const int n) const { return TEST(b, n); }
|
||||
const bool operator[](const int n) { return test(n); }
|
||||
const bool operator[](const int n) const { return test(n); }
|
||||
bool operator[](const int n) { return test(n); }
|
||||
bool operator[](const int n) const { return test(n); }
|
||||
int size() const { return sizeof(b); }
|
||||
};
|
||||
|
||||
@@ -226,8 +228,8 @@ typedef const_float_t const_celsius_float_t;
|
||||
// Helpers
|
||||
#define _RECIP(N) ((N) ? 1.0f / static_cast<float>(N) : 0.0f)
|
||||
#define _ABS(N) ((N) < 0 ? -(N) : (N))
|
||||
#define _LS(N) (N = (T)(uint32_t(N) << v))
|
||||
#define _RS(N) (N = (T)(uint32_t(N) >> v))
|
||||
#define _LS(N) (N = (T)(uint32_t(N) << p))
|
||||
#define _RS(N) (N = (T)(uint32_t(N) >> p))
|
||||
#define FI FORCE_INLINE
|
||||
|
||||
// Forward declarations
|
||||
@@ -307,9 +309,9 @@ typedef abce_float_t abce_pos_t;
|
||||
void toLogical(xy_pos_t &raw);
|
||||
void toLogical(xyz_pos_t &raw);
|
||||
void toLogical(xyze_pos_t &raw);
|
||||
void toNative(xy_pos_t &raw);
|
||||
void toNative(xyz_pos_t &raw);
|
||||
void toNative(xyze_pos_t &raw);
|
||||
void toNative(xy_pos_t &lpos);
|
||||
void toNative(xyz_pos_t &lpos);
|
||||
void toNative(xyze_pos_t &lpos);
|
||||
|
||||
//
|
||||
// Paired XY coordinates, counters, flags, etc.
|
||||
@@ -347,6 +349,10 @@ struct XYval {
|
||||
FI operator T* () { return pos; }
|
||||
// If any element is true then it's true
|
||||
FI operator bool() { return x || y; }
|
||||
// Smallest element
|
||||
FI T small() const { return _MIN(x, y); }
|
||||
// Largest element
|
||||
FI T large() const { return _MAX(x, y); }
|
||||
|
||||
// Explicit copy and copies with conversion
|
||||
FI XYval<T> copy() const { return *this; }
|
||||
@@ -405,18 +411,18 @@ struct XYval {
|
||||
FI XYval<T> operator* (const XYZEval<T> &rs) { XYval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
||||
FI XYval<T> operator/ (const XYZEval<T> &rs) const { XYval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||
FI XYval<T> operator/ (const XYZEval<T> &rs) { XYval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||
FI XYval<T> operator* (const float &v) const { XYval<T> ls = *this; ls.x *= v; ls.y *= v; return ls; }
|
||||
FI XYval<T> operator* (const float &v) { XYval<T> ls = *this; ls.x *= v; ls.y *= v; return ls; }
|
||||
FI XYval<T> operator* (const int &v) const { XYval<T> ls = *this; ls.x *= v; ls.y *= v; return ls; }
|
||||
FI XYval<T> operator* (const int &v) { XYval<T> ls = *this; ls.x *= v; ls.y *= v; return ls; }
|
||||
FI XYval<T> operator/ (const float &v) const { XYval<T> ls = *this; ls.x /= v; ls.y /= v; return ls; }
|
||||
FI XYval<T> operator/ (const float &v) { XYval<T> ls = *this; ls.x /= v; ls.y /= v; return ls; }
|
||||
FI XYval<T> operator/ (const int &v) const { XYval<T> ls = *this; ls.x /= v; ls.y /= v; return ls; }
|
||||
FI XYval<T> operator/ (const int &v) { XYval<T> ls = *this; ls.x /= v; ls.y /= v; return ls; }
|
||||
FI XYval<T> operator>>(const int &v) const { XYval<T> ls = *this; _RS(ls.x); _RS(ls.y); return ls; }
|
||||
FI XYval<T> operator>>(const int &v) { XYval<T> ls = *this; _RS(ls.x); _RS(ls.y); return ls; }
|
||||
FI XYval<T> operator<<(const int &v) const { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
||||
FI XYval<T> operator<<(const int &v) { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
||||
FI XYval<T> operator* (const float &p) const { XYval<T> ls = *this; ls.x *= p; ls.y *= p; return ls; }
|
||||
FI XYval<T> operator* (const float &p) { XYval<T> ls = *this; ls.x *= p; ls.y *= p; return ls; }
|
||||
FI XYval<T> operator* (const int &p) const { XYval<T> ls = *this; ls.x *= p; ls.y *= p; return ls; }
|
||||
FI XYval<T> operator* (const int &p) { XYval<T> ls = *this; ls.x *= p; ls.y *= p; return ls; }
|
||||
FI XYval<T> operator/ (const float &p) const { XYval<T> ls = *this; ls.x /= p; ls.y /= p; return ls; }
|
||||
FI XYval<T> operator/ (const float &p) { XYval<T> ls = *this; ls.x /= p; ls.y /= p; return ls; }
|
||||
FI XYval<T> operator/ (const int &p) const { XYval<T> ls = *this; ls.x /= p; ls.y /= p; return ls; }
|
||||
FI XYval<T> operator/ (const int &p) { XYval<T> ls = *this; ls.x /= p; ls.y /= p; return ls; }
|
||||
FI XYval<T> operator>>(const int &p) const { XYval<T> ls = *this; _RS(ls.x); _RS(ls.y); return ls; }
|
||||
FI XYval<T> operator>>(const int &p) { XYval<T> ls = *this; _RS(ls.x); _RS(ls.y); return ls; }
|
||||
FI XYval<T> operator<<(const int &p) const { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
||||
FI XYval<T> operator<<(const int &p) { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
||||
FI const XYval<T> operator-() const { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
|
||||
FI XYval<T> operator-() { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
|
||||
|
||||
@@ -430,21 +436,15 @@ struct XYval {
|
||||
FI XYval<T>& operator+=(const XYZEval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
||||
FI XYval<T>& operator-=(const XYZEval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
||||
FI XYval<T>& operator*=(const XYZEval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
||||
FI XYval<T>& operator*=(const float &v) { x *= v; y *= v; return *this; }
|
||||
FI XYval<T>& operator*=(const int &v) { x *= v; y *= v; return *this; }
|
||||
FI XYval<T>& operator>>=(const int &v) { _RS(x); _RS(y); return *this; }
|
||||
FI XYval<T>& operator<<=(const int &v) { _LS(x); _LS(y); return *this; }
|
||||
FI XYval<T>& operator*=(const float &p) { x *= p; y *= p; return *this; }
|
||||
FI XYval<T>& operator*=(const int &p) { x *= p; y *= p; return *this; }
|
||||
FI XYval<T>& operator>>=(const int &p) { _RS(x); _RS(y); return *this; }
|
||||
FI XYval<T>& operator<<=(const int &p) { _LS(x); _LS(y); return *this; }
|
||||
|
||||
// Exact comparisons. For floats a "NEAR" operation may be better.
|
||||
FI bool operator==(const XYval<T> &rs) { return x == rs.x && y == rs.y; }
|
||||
FI bool operator==(const XYZval<T> &rs) { return x == rs.x && y == rs.y; }
|
||||
FI bool operator==(const XYZEval<T> &rs) { return x == rs.x && y == rs.y; }
|
||||
FI bool operator==(const XYval<T> &rs) const { return x == rs.x && y == rs.y; }
|
||||
FI bool operator==(const XYZval<T> &rs) const { return x == rs.x && y == rs.y; }
|
||||
FI bool operator==(const XYZEval<T> &rs) const { return x == rs.x && y == rs.y; }
|
||||
FI bool operator!=(const XYval<T> &rs) { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZval<T> &rs) { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZEval<T> &rs) { return !operator==(rs); }
|
||||
FI bool operator!=(const XYval<T> &rs) const { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
||||
@@ -494,10 +494,10 @@ struct XYZval {
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; }
|
||||
#endif
|
||||
#if HAS_V_AXIS
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; }
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; }
|
||||
#endif
|
||||
#if HAS_W_AXIS
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm, const T po) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; }
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; }
|
||||
#endif
|
||||
|
||||
// Length reduced to one dimension
|
||||
@@ -506,6 +506,10 @@ struct XYZval {
|
||||
FI operator T* () { return pos; }
|
||||
// If any element is true then it's true
|
||||
FI operator bool() { return NUM_AXIS_GANG(x, || y, || z, || i, || j, || k, || u, || v, || w); }
|
||||
// Smallest element
|
||||
FI T small() const { return _MIN(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)); }
|
||||
// Largest element
|
||||
FI T large() const { return _MAX(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)); }
|
||||
|
||||
// Explicit copy and copies with conversion
|
||||
FI XYZval<T> copy() const { XYZval<T> o = *this; return o; }
|
||||
@@ -565,18 +569,18 @@ struct XYZval {
|
||||
FI XYZval<T> operator* (const XYZEval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZval<T> operator/ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZval<T> operator/ (const XYZEval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZval<T> operator* (const float &v) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZval<T> operator* (const float &v) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZval<T> operator* (const int &v) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZval<T> operator* (const int &v) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZval<T> operator/ (const float &v) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZval<T> operator/ (const float &v) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZval<T> operator/ (const int &v) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZval<T> operator/ (const int &v) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZval<T> operator>>(const int &v) const { XYZval<T> ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator>>(const int &v) { XYZval<T> ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator<<(const int &v) const { XYZval<T> ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator<<(const int &v) { XYZval<T> ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator* (const float &p) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZval<T> operator* (const float &p) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZval<T> operator* (const int &p) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZval<T> operator* (const int &p) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZval<T> operator/ (const float &p) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZval<T> operator/ (const float &p) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZval<T> operator/ (const int &p) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZval<T> operator/ (const int &p) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZval<T> operator>>(const int &p) const { XYZval<T> ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator>>(const int &p) { XYZval<T> ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator<<(const int &p) const { XYZval<T> ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI XYZval<T> operator<<(const int &p) { XYZval<T> ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI const XYZval<T> operator-() const { XYZval<T> o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; }
|
||||
FI XYZval<T> operator-() { XYZval<T> o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; }
|
||||
|
||||
@@ -593,15 +597,13 @@ struct XYZval {
|
||||
FI XYZval<T>& operator-=(const XYZEval<T> &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
|
||||
FI XYZval<T>& operator*=(const XYZEval<T> &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
|
||||
FI XYZval<T>& operator/=(const XYZEval<T> &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
|
||||
FI XYZval<T>& operator*=(const float &v) { NUM_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v, u *= v, v *= v, w *= v); return *this; }
|
||||
FI XYZval<T>& operator*=(const int &v) { NUM_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v, u *= v, v *= v, w *= v); return *this; }
|
||||
FI XYZval<T>& operator>>=(const int &v) { NUM_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; }
|
||||
FI XYZval<T>& operator<<=(const int &v) { NUM_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; }
|
||||
FI XYZval<T>& operator*=(const float &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
|
||||
FI XYZval<T>& operator*=(const int &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
|
||||
FI XYZval<T>& operator>>=(const int &p) { NUM_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; }
|
||||
FI XYZval<T>& operator<<=(const int &p) { NUM_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; }
|
||||
|
||||
// Exact comparisons. For floats a "NEAR" operation may be better.
|
||||
FI bool operator==(const XYZEval<T> &rs) { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
|
||||
FI bool operator==(const XYZEval<T> &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
|
||||
FI bool operator!=(const XYZEval<T> &rs) { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
||||
};
|
||||
|
||||
@@ -634,10 +636,10 @@ struct XYZEval {
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; }
|
||||
#endif
|
||||
#if HAS_V_AXIS
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; }
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; }
|
||||
#endif
|
||||
#if HAS_W_AXIS
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm, const T po) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pm; v = pv; }
|
||||
FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; }
|
||||
#endif
|
||||
|
||||
// Setters taking struct types and arrays
|
||||
@@ -654,11 +656,15 @@ struct XYZEval {
|
||||
#endif
|
||||
|
||||
// Length reduced to one dimension
|
||||
FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
|
||||
FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
|
||||
// Pointer to the data as a simple array
|
||||
FI operator T* () { return pos; }
|
||||
FI operator T* () { return pos; }
|
||||
// If any element is true then it's true
|
||||
FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); }
|
||||
FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); }
|
||||
// Smallest element
|
||||
FI T small() const { return _MIN(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); }
|
||||
// Largest element
|
||||
FI T large() const { return _MAX(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); }
|
||||
|
||||
// Explicit copy and copies with conversion
|
||||
FI XYZEval<T> copy() const { XYZEval<T> v = *this; return v; }
|
||||
@@ -684,76 +690,76 @@ struct XYZEval {
|
||||
FI operator const XYZval<T>&() const { return *(const XYZval<T>*)this; }
|
||||
|
||||
// Accessor via an AxisEnum (or any integer) [index]
|
||||
FI T& operator[](const int n) { return pos[n]; }
|
||||
FI const T& operator[](const int n) const { return pos[n]; }
|
||||
FI T& operator[](const int n) { return pos[n]; }
|
||||
FI const T& operator[](const int n) const { return pos[n]; }
|
||||
|
||||
// Assignment operator overrides do the expected thing
|
||||
FI XYZEval<T>& operator= (const T v) { set(LOGICAL_AXIS_LIST_1(v)); return *this; }
|
||||
FI XYZEval<T>& operator= (const XYval<T> &rs) { set(rs.x, rs.y); return *this; }
|
||||
FI XYZEval<T>& operator= (const XYZval<T> &rs) { set(NUM_AXIS_ELEM(rs)); return *this; }
|
||||
FI XYZEval<T>& operator= (const T v) { set(LOGICAL_AXIS_LIST_1(v)); return *this; }
|
||||
FI XYZEval<T>& operator= (const XYval<T> &rs) { set(rs.x, rs.y); return *this; }
|
||||
FI XYZEval<T>& operator= (const XYZval<T> &rs) { set(NUM_AXIS_ELEM(rs)); return *this; }
|
||||
|
||||
// Override other operators to get intuitive behaviors
|
||||
FI XYZEval<T> operator+ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||
FI XYZEval<T> operator+ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||
FI XYZEval<T> operator- (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
||||
FI XYZEval<T> operator- (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
||||
FI XYZEval<T> operator* (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
||||
FI XYZEval<T> operator* (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
||||
FI XYZEval<T> operator/ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||
FI XYZEval<T> operator/ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const float &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZEval<T> operator* (const float &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZEval<T> operator* (const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZEval<T> operator* (const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v, ls.u *= v, ls.v *= v, ls.w *= v ); return ls; }
|
||||
FI XYZEval<T> operator/ (const float &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZEval<T> operator/ (const float &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZEval<T> operator/ (const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZEval<T> operator/ (const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v, ls.u /= v, ls.v /= v, ls.w /= v ); return ls; }
|
||||
FI XYZEval<T> operator>>(const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZEval<T> operator>>(const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZEval<T> operator<<(const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI XYZEval<T> operator<<(const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI const XYZEval<T> operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); }
|
||||
FI XYZEval<T> operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); }
|
||||
FI XYZEval<T> operator+ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||
FI XYZEval<T> operator+ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||
FI XYZEval<T> operator- (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
||||
FI XYZEval<T> operator- (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
||||
FI XYZEval<T> operator* (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
||||
FI XYZEval<T> operator* (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
||||
FI XYZEval<T> operator/ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||
FI XYZEval<T> operator/ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZval<T> &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZval<T> &rs) { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator+ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator- (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator/ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
|
||||
FI XYZEval<T> operator* (const float &p) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZEval<T> operator* (const float &p) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZEval<T> operator* (const int &p) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZEval<T> operator* (const int &p) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; }
|
||||
FI XYZEval<T> operator/ (const float &p) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZEval<T> operator/ (const float &p) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZEval<T> operator/ (const int &p) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZEval<T> operator/ (const int &p) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; }
|
||||
FI XYZEval<T> operator>>(const int &p) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZEval<T> operator>>(const int &p) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; }
|
||||
FI XYZEval<T> operator<<(const int &p) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI XYZEval<T> operator<<(const int &p) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; }
|
||||
FI const XYZEval<T> operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); }
|
||||
FI XYZEval<T> operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); }
|
||||
|
||||
// Modifier operators
|
||||
FI XYZEval<T>& operator+=(const XYval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
||||
FI XYZEval<T>& operator-=(const XYval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
||||
FI XYZEval<T>& operator*=(const XYval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
||||
FI XYZEval<T>& operator/=(const XYval<T> &rs) { x /= rs.x; y /= rs.y; return *this; }
|
||||
FI XYZEval<T>& operator+=(const XYZval<T> &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
|
||||
FI XYZEval<T>& operator-=(const XYZval<T> &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator*=(const XYZval<T> &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator/=(const XYZval<T> &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator+=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
|
||||
FI XYZEval<T>& operator-=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator*=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator/=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v, i *= v, j *= v, k *= v, u *= v, v *= v, w *= v); return *this; }
|
||||
FI XYZEval<T>& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; }
|
||||
FI XYZEval<T>& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; }
|
||||
FI XYZEval<T>& operator+=(const XYval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
||||
FI XYZEval<T>& operator-=(const XYval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
||||
FI XYZEval<T>& operator*=(const XYval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
||||
FI XYZEval<T>& operator/=(const XYval<T> &rs) { x /= rs.x; y /= rs.y; return *this; }
|
||||
FI XYZEval<T>& operator+=(const XYZval<T> &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
|
||||
FI XYZEval<T>& operator-=(const XYZval<T> &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator*=(const XYZval<T> &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator/=(const XYZval<T> &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator+=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
|
||||
FI XYZEval<T>& operator-=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator*=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator/=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
|
||||
FI XYZEval<T>& operator*=(const T &p) { LOGICAL_AXIS_CODE(e *= p, x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
|
||||
FI XYZEval<T>& operator>>=(const int &p) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; }
|
||||
FI XYZEval<T>& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; }
|
||||
|
||||
// Exact comparisons. For floats a "NEAR" operation may be better.
|
||||
FI bool operator==(const XYZval<T> &rs) { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
|
||||
FI bool operator==(const XYZval<T> &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
|
||||
FI bool operator!=(const XYZval<T> &rs) { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
||||
FI bool operator==(const XYZval<T> &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
|
||||
FI bool operator==(const XYZEval<T> &rs) const { return true LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
|
||||
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
||||
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
||||
};
|
||||
|
||||
#undef _RECIP
|
||||
|
@@ -96,22 +96,23 @@ void BDS_Leveling::process() {
|
||||
const float z_sensor = (tmp & 0x3FF) / 100.0f;
|
||||
if (cur_z < 0) config_state = 0;
|
||||
//float abs_z = current_position.z > cur_z ? (current_position.z - cur_z) : (cur_z - current_position.z);
|
||||
if ( cur_z < config_state * 0.1f
|
||||
&& config_state > 0
|
||||
&& old_cur_z == cur_z
|
||||
&& old_buf_z == current_position.z
|
||||
&& z_sensor < (MAX_BD_HEIGHT)
|
||||
) {
|
||||
babystep.set_mm(Z_AXIS, cur_z - z_sensor);
|
||||
#if ENABLED(DEBUG_OUT_BD)
|
||||
SERIAL_ECHOLNPGM("BD:", z_sensor, ", Z:", cur_z, "|", current_position.z);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
babystep.set_mm(Z_AXIS, 0);
|
||||
//if (old_cur_z <= cur_z) Z_DIR_WRITE(!INVERT_Z_DIR);
|
||||
stepper.set_directions();
|
||||
}
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
if (cur_z < config_state * 0.1f
|
||||
&& config_state > 0
|
||||
&& old_cur_z == cur_z
|
||||
&& old_buf_z == current_position.z
|
||||
&& z_sensor < (MAX_BD_HEIGHT)
|
||||
) {
|
||||
babystep.set_mm(Z_AXIS, cur_z - z_sensor);
|
||||
#if ENABLED(DEBUG_OUT_BD)
|
||||
SERIAL_ECHOLNPGM("BD:", z_sensor, ", Z:", cur_z, "|", current_position.z);
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
babystep.set_mm(Z_AXIS, 0); //if (old_cur_z <= cur_z) Z_DIR_WRITE(!INVERT_Z_DIR);
|
||||
stepper.set_directions();
|
||||
}
|
||||
#endif
|
||||
old_cur_z = cur_z;
|
||||
old_buf_z = current_position.z;
|
||||
endstops.bdp_state_update(z_sensor <= 0.01f);
|
||||
|
@@ -57,6 +57,7 @@ bool leveling_is_valid() {
|
||||
* Enable: Current position = "unleveled" physical position
|
||||
*/
|
||||
void set_bed_leveling_enabled(const bool enable/*=true*/) {
|
||||
DEBUG_SECTION(log_sble, "set_bed_leveling_enabled", DEBUGGING(LEVELING));
|
||||
|
||||
const bool can_change = TERN1(AUTO_BED_LEVELING_BILINEAR, !enable || leveling_is_valid());
|
||||
|
||||
@@ -75,9 +76,9 @@ void set_bed_leveling_enabled(const bool enable/*=true*/) {
|
||||
planner.synchronize();
|
||||
|
||||
// Get the corrected leveled / unleveled position
|
||||
planner.apply_modifiers(current_position); // Physical position with all modifiers
|
||||
planner.leveling_active ^= true; // Toggle leveling between apply and unapply
|
||||
planner.unapply_modifiers(current_position); // Logical position with modifiers removed
|
||||
planner.apply_modifiers(current_position, true); // Physical position with all modifiers
|
||||
planner.leveling_active ^= true; // Toggle leveling between apply and unapply
|
||||
planner.unapply_modifiers(current_position, true); // Logical position with modifiers removed
|
||||
|
||||
sync_plan_position();
|
||||
_report_leveling();
|
||||
|
@@ -260,7 +260,7 @@ bool unified_bed_leveling::sanity_check() {
|
||||
*/
|
||||
void GcodeSuite::M1004() {
|
||||
|
||||
#define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "")
|
||||
#define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34\n", "")
|
||||
#define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R")
|
||||
|
||||
#if HAS_HOTEND
|
||||
@@ -280,7 +280,7 @@ bool unified_bed_leveling::sanity_check() {
|
||||
#endif
|
||||
|
||||
process_subcommands_now(FPSTR(G28_STR)); // Home
|
||||
process_subcommands_now(F(ALIGN_GCODE "\n" // Align multi z axis if available
|
||||
process_subcommands_now(F(ALIGN_GCODE // Align multi z axis if available
|
||||
PROBE_GCODE "\n" // Build mesh with available hardware
|
||||
"G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice
|
||||
|
||||
|
@@ -407,7 +407,7 @@ void unified_bed_leveling::G29() {
|
||||
z_values[x][x2] += 9.999f; // We want the altered line several mesh points thick
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
ExtUI::onMeshUpdate(x, x, z_values[x][x]);
|
||||
ExtUI::onMeshUpdate(x, (x2), z_values[x][x2]);
|
||||
ExtUI::onMeshUpdate(x, x2, z_values[x][x2]);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
@@ -336,9 +336,9 @@
|
||||
#if IS_SCARA
|
||||
#define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm
|
||||
#elif ENABLED(DELTA)
|
||||
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND)
|
||||
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DEFAULT_SEGMENTS_PER_SECOND)
|
||||
#elif ENABLED(POLARGRAPH)
|
||||
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND)
|
||||
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DEFAULT_SEGMENTS_PER_SECOND)
|
||||
#else // CARTESIAN
|
||||
#ifdef LEVELED_SEGMENT_LENGTH
|
||||
#define DELTA_SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH
|
||||
@@ -423,10 +423,12 @@
|
||||
LIMIT(icell.x, 0, GRID_MAX_CELLS_X);
|
||||
LIMIT(icell.y, 0, GRID_MAX_CELLS_Y);
|
||||
|
||||
float z_x0y0 = z_values[icell.x ][icell.y ], // z at lower left corner
|
||||
z_x1y0 = z_values[icell.x+1][icell.y ], // z at upper left corner
|
||||
z_x0y1 = z_values[icell.x ][icell.y+1], // z at lower right corner
|
||||
z_x1y1 = z_values[icell.x+1][icell.y+1]; // z at upper right corner
|
||||
const int8_t ncellx = _MIN(icell.x+1, GRID_MAX_CELLS_X),
|
||||
ncelly = _MIN(icell.y+1, GRID_MAX_CELLS_Y);
|
||||
float z_x0y0 = z_values[icell.x][icell.y], // z at lower left corner
|
||||
z_x1y0 = z_values[ncellx ][icell.y], // z at upper left corner
|
||||
z_x0y1 = z_values[icell.x][ncelly ], // z at lower right corner
|
||||
z_x1y1 = z_values[ncellx ][ncelly ]; // z at upper right corner
|
||||
|
||||
if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating planner.leveling_active (G29 A)
|
||||
if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points
|
||||
|
@@ -38,8 +38,6 @@ bool BLTouch::od_5v_mode; // Initialized by settings.load, 0 = Open Drai
|
||||
#include "../module/servo.h"
|
||||
#include "../module/probe.h"
|
||||
|
||||
void stop();
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../core/debug_out.h"
|
||||
|
||||
|
@@ -40,6 +40,9 @@ uint8_t ControllerFan::speed;
|
||||
|
||||
void ControllerFan::setup() {
|
||||
SET_OUTPUT(CONTROLLER_FAN_PIN);
|
||||
#ifdef CONTROLLER_FAN2_PIN
|
||||
SET_OUTPUT(CONTROLLER_FAN2_PIN);
|
||||
#endif
|
||||
init();
|
||||
}
|
||||
|
||||
@@ -72,6 +75,22 @@ void ControllerFan::update() {
|
||||
? settings.active_speed : settings.idle_speed
|
||||
);
|
||||
|
||||
speed = CALC_FAN_SPEED(speed);
|
||||
|
||||
#if FAN_KICKSTART_TIME
|
||||
static millis_t fan_kick_end = 0;
|
||||
if (speed > FAN_OFF_PWM) {
|
||||
if (!fan_kick_end) {
|
||||
fan_kick_end = ms + FAN_KICKSTART_TIME; // May be longer based on slow update interval for controller fn check. Sets minimum
|
||||
speed = FAN_KICKSTART_POWER;
|
||||
}
|
||||
else if (PENDING(ms, fan_kick_end))
|
||||
speed = FAN_KICKSTART_POWER;
|
||||
}
|
||||
else
|
||||
fan_kick_end = 0;
|
||||
#endif
|
||||
|
||||
#if ENABLED(FAN_SOFT_PWM)
|
||||
thermalManager.soft_pwm_controller_speed = speed;
|
||||
#else
|
||||
@@ -79,6 +98,13 @@ void ControllerFan::update() {
|
||||
hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
|
||||
else
|
||||
WRITE(CONTROLLER_FAN_PIN, speed > 0);
|
||||
|
||||
#ifdef CONTROLLER_FAN2_PIN
|
||||
if (PWM_PIN(CONTROLLER_FAN2_PIN))
|
||||
hal.set_pwm_duty(pin_t(CONTROLLER_FAN2_PIN), speed);
|
||||
else
|
||||
WRITE(CONTROLLER_FAN2_PIN, speed > 0);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
@@ -33,6 +33,9 @@
|
||||
// Static data members
|
||||
bool EmergencyParser::killed_by_M112, // = false
|
||||
EmergencyParser::quickstop_by_M410,
|
||||
#if ENABLED(SDSUPPORT)
|
||||
EmergencyParser::sd_abort_by_M524,
|
||||
#endif
|
||||
EmergencyParser::enabled;
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
|
@@ -49,7 +49,7 @@ class EmergencyParser {
|
||||
|
||||
public:
|
||||
|
||||
// Currently looking for: M108, M112, M410, M876 S[0-9], S000, P000, R000
|
||||
// Currently looking for: M108, M112, M410, M524, M876 S[0-9], S000, P000, R000
|
||||
enum State : uint8_t {
|
||||
EP_RESET,
|
||||
EP_N,
|
||||
@@ -58,6 +58,9 @@ public:
|
||||
EP_M10, EP_M108,
|
||||
EP_M11, EP_M112,
|
||||
EP_M4, EP_M41, EP_M410,
|
||||
#if ENABLED(SDSUPPORT)
|
||||
EP_M5, EP_M52, EP_M524,
|
||||
#endif
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
EP_M8, EP_M87, EP_M876, EP_M876S, EP_M876SN,
|
||||
#endif
|
||||
@@ -76,6 +79,10 @@ public:
|
||||
static bool killed_by_M112;
|
||||
static bool quickstop_by_M410;
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
static bool sd_abort_by_M524;
|
||||
#endif
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
static uint8_t M876_reason;
|
||||
#endif
|
||||
@@ -145,6 +152,9 @@ public:
|
||||
case ' ': break;
|
||||
case '1': state = EP_M1; break;
|
||||
case '4': state = EP_M4; break;
|
||||
#if ENABLED(SDSUPPORT)
|
||||
case '5': state = EP_M5; break;
|
||||
#endif
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
case '8': state = EP_M8; break;
|
||||
#endif
|
||||
@@ -165,6 +175,11 @@ public:
|
||||
case EP_M4: state = (c == '1') ? EP_M41 : EP_IGNORE; break;
|
||||
case EP_M41: state = (c == '0') ? EP_M410 : EP_IGNORE; break;
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
case EP_M5: state = (c == '2') ? EP_M52 : EP_IGNORE; break;
|
||||
case EP_M52: state = (c == '4') ? EP_M524 : EP_IGNORE; break;
|
||||
#endif
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
|
||||
case EP_M8: state = (c == '7') ? EP_M87 : EP_IGNORE; break;
|
||||
@@ -200,6 +215,9 @@ public:
|
||||
case EP_M108: wait_for_user = wait_for_heatup = false; break;
|
||||
case EP_M112: killed_by_M112 = true; break;
|
||||
case EP_M410: quickstop_by_M410 = true; break;
|
||||
#if ENABLED(SDSUPPORT)
|
||||
case EP_M524: sd_abort_by_M524 = true; break;
|
||||
#endif
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
case EP_M876SN: hostui.handle_response(M876_reason); break;
|
||||
#endif
|
||||
|
@@ -111,20 +111,29 @@ void HostUI::action(FSTR_P const fstr, const bool eol) {
|
||||
if (eol) SERIAL_EOL();
|
||||
}
|
||||
|
||||
void HostUI::prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char/*='\0'*/) {
|
||||
void HostUI::prompt_plus(const bool pgm, FSTR_P const ptype, const char * const str, const char extra_char/*='\0'*/) {
|
||||
prompt(ptype, false);
|
||||
PORT_REDIRECT(SerialMask::All);
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_ECHOF(fstr);
|
||||
if (pgm)
|
||||
SERIAL_ECHOPGM_P(str);
|
||||
else
|
||||
SERIAL_ECHO(str);
|
||||
if (extra_char != '\0') SERIAL_CHAR(extra_char);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
void HostUI::prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char/*='\0'*/) {
|
||||
prompt_end();
|
||||
host_prompt_reason = reason;
|
||||
prompt_plus(F("begin"), fstr, extra_char);
|
||||
}
|
||||
void HostUI::prompt_button(FSTR_P const fstr) { prompt_plus(F("button"), fstr); }
|
||||
void HostUI::prompt_begin(const PromptReason reason, const char * const cstr, const char extra_char/*='\0'*/) {
|
||||
prompt_end();
|
||||
host_prompt_reason = reason;
|
||||
prompt_plus(F("begin"), cstr, extra_char);
|
||||
}
|
||||
|
||||
void HostUI::prompt_end() { prompt(F("end")); }
|
||||
void HostUI::prompt_show() { prompt(F("show")); }
|
||||
|
||||
@@ -133,14 +142,26 @@ void HostUI::action(FSTR_P const fstr, const bool eol) {
|
||||
if (btn2) prompt_button(btn2);
|
||||
prompt_show();
|
||||
}
|
||||
|
||||
void HostUI::prompt_button(FSTR_P const fstr) { prompt_plus(F("button"), fstr); }
|
||||
void HostUI::prompt_button(const char * const cstr) { prompt_plus(F("button"), cstr); }
|
||||
|
||||
void HostUI::prompt_do(const PromptReason reason, FSTR_P const fstr, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) {
|
||||
prompt_begin(reason, fstr);
|
||||
_prompt_show(btn1, btn2);
|
||||
}
|
||||
void HostUI::prompt_do(const PromptReason reason, const char * const cstr, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) {
|
||||
prompt_begin(reason, cstr);
|
||||
_prompt_show(btn1, btn2);
|
||||
}
|
||||
void HostUI::prompt_do(const PromptReason reason, FSTR_P const fstr, const char extra_char, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) {
|
||||
prompt_begin(reason, fstr, extra_char);
|
||||
_prompt_show(btn1, btn2);
|
||||
}
|
||||
void HostUI::prompt_do(const PromptReason reason, const char * const cstr, const char extra_char, FSTR_P const btn1/*=nullptr*/, FSTR_P const btn2/*=nullptr*/) {
|
||||
prompt_begin(reason, cstr, extra_char);
|
||||
_prompt_show(btn1, btn2);
|
||||
}
|
||||
|
||||
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
||||
void HostUI::filament_load_prompt() {
|
||||
|
@@ -79,7 +79,14 @@ class HostUI {
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
private:
|
||||
static void prompt(FSTR_P const ptype, const bool eol=true);
|
||||
static void prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char='\0');
|
||||
static void prompt_plus(const bool pgm, FSTR_P const ptype, const char * const str, const char extra_char='\0');
|
||||
static void prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char='\0') {
|
||||
prompt_plus(true, ptype, FTOP(fstr), extra_char);
|
||||
}
|
||||
static void prompt_plus(FSTR_P const ptype, const char * const cstr, const char extra_char='\0') {
|
||||
prompt_plus(false, ptype, cstr, extra_char);
|
||||
}
|
||||
|
||||
static void prompt_show();
|
||||
static void _prompt_show(FSTR_P const btn1, FSTR_P const btn2);
|
||||
|
||||
@@ -93,10 +100,17 @@ class HostUI {
|
||||
static void notify(const char * const message);
|
||||
|
||||
static void prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char='\0');
|
||||
static void prompt_button(FSTR_P const fstr);
|
||||
static void prompt_begin(const PromptReason reason, const char * const cstr, const char extra_char='\0');
|
||||
static void prompt_end();
|
||||
|
||||
static void prompt_button(FSTR_P const fstr);
|
||||
static void prompt_button(const char * const cstr);
|
||||
|
||||
static void prompt_do(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr);
|
||||
static void prompt_do(const PromptReason reason, const char * const cstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr);
|
||||
static void prompt_do(const PromptReason reason, FSTR_P const pstr, const char extra_char, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr);
|
||||
static void prompt_do(const PromptReason reason, const char * const cstr, const char extra_char, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr);
|
||||
|
||||
static void prompt_open(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr) {
|
||||
if (host_prompt_reason == PROMPT_NOT_DEFINED) prompt_do(reason, pstr, btn1, btn2);
|
||||
}
|
||||
|
@@ -30,18 +30,6 @@
|
||||
|
||||
#include "leds.h"
|
||||
|
||||
#if ENABLED(BLINKM)
|
||||
#include "blinkm.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(PCA9632)
|
||||
#include "pca9632.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(PCA9533)
|
||||
#include "pca9533.h"
|
||||
#endif
|
||||
|
||||
#if EITHER(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL)
|
||||
#include "../../feature/caselight.h"
|
||||
#endif
|
||||
@@ -69,6 +57,44 @@ void LEDLights::setup() {
|
||||
#if ENABLED(RGBW_LED)
|
||||
if (PWM_PIN(RGB_LED_W_PIN)) SET_PWM(RGB_LED_W_PIN); else SET_OUTPUT(RGB_LED_W_PIN);
|
||||
#endif
|
||||
|
||||
#if ENABLED(RGB_STARTUP_TEST)
|
||||
int8_t led_pin_count = 0;
|
||||
if (PWM_PIN(RGB_LED_R_PIN) && PWM_PIN(RGB_LED_G_PIN) && PWM_PIN(RGB_LED_B_PIN)) led_pin_count = 3;
|
||||
#if ENABLED(RGBW_LED)
|
||||
if (PWM_PIN(RGB_LED_W_PIN) && led_pin_count) led_pin_count++;
|
||||
#endif
|
||||
// Startup animation
|
||||
if (led_pin_count) {
|
||||
// blackout
|
||||
if (PWM_PIN(RGB_LED_R_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_R_PIN), 0); else WRITE(RGB_LED_R_PIN, LOW);
|
||||
if (PWM_PIN(RGB_LED_G_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_G_PIN), 0); else WRITE(RGB_LED_G_PIN, LOW);
|
||||
if (PWM_PIN(RGB_LED_B_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_B_PIN), 0); else WRITE(RGB_LED_B_PIN, LOW);
|
||||
#if ENABLED(RGBW_LED)
|
||||
if (PWM_PIN(RGB_LED_W_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_W_PIN), 0);
|
||||
else WRITE(RGB_LED_W_PIN, LOW);
|
||||
#endif
|
||||
delay(200);
|
||||
|
||||
LOOP_L_N(i, led_pin_count) {
|
||||
LOOP_LE_N(b, 200) {
|
||||
const uint16_t led_pwm = b <= 100 ? b : 200 - b;
|
||||
if (i == 0 && PWM_PIN(RGB_LED_R_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_R_PIN), led_pwm); else WRITE(RGB_LED_R_PIN, b < 100 ? HIGH : LOW);
|
||||
if (i == 1 && PWM_PIN(RGB_LED_G_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_G_PIN), led_pwm); else WRITE(RGB_LED_G_PIN, b < 100 ? HIGH : LOW);
|
||||
if (i == 2 && PWM_PIN(RGB_LED_B_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_B_PIN), led_pwm); else WRITE(RGB_LED_B_PIN, b < 100 ? HIGH : LOW);
|
||||
#if ENABLED(RGBW_LED)
|
||||
if (i == 3){
|
||||
if (PWM_PIN(RGB_LED_W_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_W_PIN), led_pwm);
|
||||
else WRITE(RGB_LED_W_PIN, b < 100 ? HIGH : LOW);
|
||||
delay(RGB_STARTUP_TEST_INNER_MS);//More slowing for ending
|
||||
}
|
||||
#endif
|
||||
delay(RGB_STARTUP_TEST_INNER_MS);
|
||||
}
|
||||
}
|
||||
delay(500);
|
||||
}
|
||||
#endif // RGB_STARTUP_TEST
|
||||
#endif
|
||||
TERN_(NEOPIXEL_LED, neo.init());
|
||||
TERN_(PCA9533, PCA9533_init());
|
||||
|
@@ -40,6 +40,18 @@
|
||||
#undef _NEOPIXEL_INCLUDE_
|
||||
#endif
|
||||
|
||||
#if ENABLED(BLINKM)
|
||||
#include "blinkm.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(PCA9533)
|
||||
#include "pca9533.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(PCA9632)
|
||||
#include "pca9632.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* LEDcolor type for use with leds.set_color
|
||||
*/
|
||||
@@ -107,6 +119,13 @@ typedef struct LEDColor {
|
||||
|
||||
class LEDLights {
|
||||
public:
|
||||
#if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED)
|
||||
static LEDColor color; // last non-off color
|
||||
static bool lights_on; // the last set color was "on"
|
||||
#else
|
||||
static constexpr bool lights_on = true;
|
||||
#endif
|
||||
|
||||
LEDLights() {} // ctor
|
||||
|
||||
static void setup(); // init()
|
||||
@@ -142,15 +161,10 @@ public:
|
||||
static LEDColor get_color() { return lights_on ? color : LEDColorOff(); }
|
||||
#endif
|
||||
|
||||
#if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED)
|
||||
static LEDColor color; // last non-off color
|
||||
static bool lights_on; // the last set color was "on"
|
||||
#endif
|
||||
|
||||
#if ENABLED(LED_CONTROL_MENU)
|
||||
static void toggle(); // swap "off" with color
|
||||
#endif
|
||||
#if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED)
|
||||
#if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) || LED_POWEROFF_TIMEOUT > 0
|
||||
static void update() { set_color(color); }
|
||||
#endif
|
||||
|
||||
|
@@ -54,7 +54,8 @@ MMU2 mmu2;
|
||||
#define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0)
|
||||
#define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds
|
||||
|
||||
#define MMU2_COMMAND(S) tx_str(F(S "\n"))
|
||||
#define MMU2_SEND(S) tx_str(F(S "\n"))
|
||||
#define MMU2_RECV(S) rx_str(F(S "\n"))
|
||||
|
||||
#if ENABLED(MMU_EXTRUDER_SENSOR)
|
||||
uint8_t mmu_idl_sens = 0;
|
||||
@@ -131,7 +132,7 @@ void MMU2::reset() {
|
||||
safe_delay(20);
|
||||
WRITE(MMU2_RST_PIN, HIGH);
|
||||
#else
|
||||
MMU2_COMMAND("X0"); // Send soft reset
|
||||
MMU2_SEND("X0"); // Send soft reset
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -157,11 +158,9 @@ void MMU2::mmu_loop() {
|
||||
case -1:
|
||||
if (rx_start()) {
|
||||
prev_P0_request = millis(); // Initialize finda sensor timeout
|
||||
|
||||
DEBUG_ECHOLNPGM("MMU => 'start'");
|
||||
DEBUG_ECHOLNPGM("MMU <= 'S1'");
|
||||
|
||||
MMU2_COMMAND("S1"); // Read Version
|
||||
MMU2_SEND("S1"); // Read Version
|
||||
state = -2;
|
||||
}
|
||||
else if (millis() > 30000) { // 30sec after reset disable MMU
|
||||
@@ -173,10 +172,8 @@ void MMU2::mmu_loop() {
|
||||
case -2:
|
||||
if (rx_ok()) {
|
||||
sscanf(rx_buffer, "%huok\n", &version);
|
||||
|
||||
DEBUG_ECHOLNPGM("MMU => ", version, "\nMMU <= 'S2'");
|
||||
|
||||
MMU2_COMMAND("S2"); // Read Build Number
|
||||
MMU2_SEND("S2"); // Read Build Number
|
||||
state = -3;
|
||||
}
|
||||
break;
|
||||
@@ -191,14 +188,12 @@ void MMU2::mmu_loop() {
|
||||
|
||||
#if ENABLED(MMU2_MODE_12V)
|
||||
DEBUG_ECHOLNPGM("MMU <= 'M1'");
|
||||
|
||||
MMU2_COMMAND("M1"); // Stealth Mode
|
||||
MMU2_SEND("M1"); // Stealth Mode
|
||||
state = -5;
|
||||
|
||||
#else
|
||||
DEBUG_ECHOLNPGM("MMU <= 'P0'");
|
||||
|
||||
MMU2_COMMAND("P0"); // Read FINDA
|
||||
MMU2_SEND("P0"); // Read FINDA
|
||||
state = -4;
|
||||
#endif
|
||||
}
|
||||
@@ -209,10 +204,8 @@ void MMU2::mmu_loop() {
|
||||
// response to M1
|
||||
if (rx_ok()) {
|
||||
DEBUG_ECHOLNPGM("MMU => ok");
|
||||
|
||||
DEBUG_ECHOLNPGM("MMU <= 'P0'");
|
||||
|
||||
MMU2_COMMAND("P0"); // Read FINDA
|
||||
MMU2_SEND("P0"); // Read FINDA
|
||||
state = -4;
|
||||
}
|
||||
break;
|
||||
@@ -250,14 +243,13 @@ void MMU2::mmu_loop() {
|
||||
else if (cmd == MMU_CMD_C0) {
|
||||
// continue loading
|
||||
DEBUG_ECHOLNPGM("MMU <= 'C0'");
|
||||
MMU2_COMMAND("C0");
|
||||
MMU2_SEND("C0");
|
||||
state = 3; // wait for response
|
||||
}
|
||||
else if (cmd == MMU_CMD_U0) {
|
||||
// unload current
|
||||
DEBUG_ECHOLNPGM("MMU <= 'U0'");
|
||||
|
||||
MMU2_COMMAND("U0");
|
||||
MMU2_SEND("U0");
|
||||
state = 3; // wait for response
|
||||
}
|
||||
else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E0 + EXTRUDERS - 1)) {
|
||||
@@ -270,7 +262,7 @@ void MMU2::mmu_loop() {
|
||||
else if (cmd == MMU_CMD_R0) {
|
||||
// recover after eject
|
||||
DEBUG_ECHOLNPGM("MMU <= 'R0'");
|
||||
MMU2_COMMAND("R0");
|
||||
MMU2_SEND("R0");
|
||||
state = 3; // wait for response
|
||||
}
|
||||
else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F0 + EXTRUDERS - 1)) {
|
||||
@@ -285,7 +277,7 @@ void MMU2::mmu_loop() {
|
||||
cmd = MMU_CMD_NONE;
|
||||
}
|
||||
else if (ELAPSED(millis(), prev_P0_request + 300)) {
|
||||
MMU2_COMMAND("P0"); // Read FINDA
|
||||
MMU2_SEND("P0"); // Read FINDA
|
||||
state = 2; // wait for response
|
||||
}
|
||||
|
||||
@@ -314,7 +306,7 @@ void MMU2::mmu_loop() {
|
||||
if (mmu_idl_sens) {
|
||||
if (FILAMENT_PRESENT() && mmu_loading_flag) {
|
||||
DEBUG_ECHOLNPGM("MMU <= 'A'");
|
||||
MMU2_COMMAND("A"); // send 'abort' request
|
||||
MMU2_SEND("A"); // send 'abort' request
|
||||
mmu_idl_sens = 0;
|
||||
DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT");
|
||||
}
|
||||
@@ -327,9 +319,9 @@ void MMU2::mmu_loop() {
|
||||
const bool keep_trying = !mmu2s_triggered && last_cmd == MMU_CMD_C0;
|
||||
if (keep_trying) {
|
||||
// MMU ok received but filament sensor not triggered, retrying...
|
||||
DEBUG_ECHOLNPGM("MMU => 'ok' (filament not present in gears)");
|
||||
DEBUG_ECHOLNPGM("MMU => 'ok' (no filament in gears)");
|
||||
DEBUG_ECHOLNPGM("MMU <= 'C0' (keep trying)");
|
||||
MMU2_COMMAND("C0");
|
||||
MMU2_SEND("C0");
|
||||
}
|
||||
#else
|
||||
constexpr bool keep_trying = false;
|
||||
@@ -361,7 +353,7 @@ void MMU2::mmu_loop() {
|
||||
*/
|
||||
bool MMU2::rx_start() {
|
||||
// check for start message
|
||||
return rx_str(F("start\n"));
|
||||
return MMU2_RECV("start");
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -440,7 +432,7 @@ void MMU2::clear_rx_buffer() {
|
||||
* Check if we received 'ok' from MMU
|
||||
*/
|
||||
bool MMU2::rx_ok() {
|
||||
if (rx_str(F("ok\n"))) {
|
||||
if (MMU2_RECV("ok")) {
|
||||
prev_P0_request = millis();
|
||||
return true;
|
||||
}
|
||||
@@ -585,7 +577,7 @@ static void mmu2_not_responding() {
|
||||
command(MMU_CMD_T0 + index);
|
||||
manage_response(true, true);
|
||||
mmu_continue_loading();
|
||||
command(MMU_CMD_C0);
|
||||
//command(MMU_CMD_C0);
|
||||
extruder = index;
|
||||
active_extruder = 0;
|
||||
|
||||
@@ -653,13 +645,34 @@ static void mmu2_not_responding() {
|
||||
}
|
||||
|
||||
void MMU2::mmu_continue_loading() {
|
||||
// Try to load the filament a limited number of times
|
||||
bool fil_present = 0;
|
||||
for (uint8_t i = 0; i < MMU_LOADING_ATTEMPTS_NR; i++) {
|
||||
DEBUG_ECHOLNPGM("Additional load attempt #", i);
|
||||
if (FILAMENT_PRESENT()) break;
|
||||
DEBUG_ECHOLNPGM("Load attempt #", i + 1);
|
||||
|
||||
// Done as soon as filament is present
|
||||
fil_present = FILAMENT_PRESENT();
|
||||
if (fil_present) break;
|
||||
|
||||
// Attempt to load the filament, 1mm at a time, for 3s
|
||||
command(MMU_CMD_C0);
|
||||
stepper.enable_extruder();
|
||||
const millis_t expire_ms = millis() + 3000;
|
||||
do {
|
||||
current_position.e += 1;
|
||||
line_to_current_position(MMU_LOAD_FEEDRATE);
|
||||
planner.synchronize();
|
||||
// When (T0 rx->ok) load is ready, but in fact it did not load
|
||||
// successfully or an overload created pressure in the extruder.
|
||||
// Send (C0) to load more and move E_AXIS a little to release pressure.
|
||||
if ((fil_present = FILAMENT_PRESENT())) MMU2_SEND("A");
|
||||
} while (!fil_present && PENDING(millis(), expire_ms));
|
||||
stepper.disable_extruder();
|
||||
manage_response(true, true);
|
||||
}
|
||||
if (!FILAMENT_PRESENT()) {
|
||||
|
||||
// Was the filament still missing in the last check?
|
||||
if (!fil_present) {
|
||||
DEBUG_ECHOLNPGM("Filament never reached sensor, runout");
|
||||
filament_runout();
|
||||
}
|
||||
@@ -682,7 +695,7 @@ static void mmu2_not_responding() {
|
||||
command(MMU_CMD_T0 + index);
|
||||
manage_response(true, true);
|
||||
command(MMU_CMD_C0);
|
||||
extruder = index; //filament change is finished
|
||||
extruder = index; // Filament change is finished
|
||||
active_extruder = 0;
|
||||
stepper.enable_extruder();
|
||||
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder);
|
||||
@@ -861,7 +874,7 @@ void MMU2::filament_runout() {
|
||||
if (cmd == MMU_CMD_NONE && last_cmd == MMU_CMD_C0) {
|
||||
if (present && !mmu2s_triggered) {
|
||||
DEBUG_ECHOLNPGM("MMU <= 'A'");
|
||||
tx_str(F("A\n"));
|
||||
MMU2_SEND("A");
|
||||
}
|
||||
// Slowly spin the extruder during C0
|
||||
else {
|
||||
|
@@ -86,6 +86,7 @@ private:
|
||||
#endif
|
||||
|
||||
#if ENABLED(MMU_EXTRUDER_SENSOR)
|
||||
#define MMU_LOAD_FEEDRATE 19.02f // (mm/s)
|
||||
static void mmu_continue_loading();
|
||||
#endif
|
||||
|
||||
|
@@ -474,9 +474,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
|
||||
if (unload_length)
|
||||
unload_filament(unload_length, show_lcd, PAUSE_MODE_CHANGE_FILAMENT);
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
set_duplication_enabled(saved_ext_dup_mode, saved_ext);
|
||||
#endif
|
||||
TERN_(DUAL_X_CARRIAGE, set_duplication_enabled(saved_ext_dup_mode, saved_ext));
|
||||
|
||||
// Disable the Extruder for manual change
|
||||
disable_active_extruder();
|
||||
@@ -593,9 +591,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
|
||||
}
|
||||
idle_no_sleep();
|
||||
}
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
set_duplication_enabled(saved_ext_dup_mode, saved_ext);
|
||||
#endif
|
||||
TERN_(DUAL_X_CARRIAGE, set_duplication_enabled(saved_ext_dup_mode, saved_ext));
|
||||
}
|
||||
|
||||
/**
|
||||
|
@@ -53,7 +53,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor
|
||||
void PowerMonitor::draw_current() {
|
||||
const float amps = getAmps();
|
||||
lcd_put_u8str(amps < 100 ? ftostr31ns(amps) : ui16tostr4rj((uint16_t)amps));
|
||||
lcd_put_lchar('A');
|
||||
lcd_put_u8str(F("A"));
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -61,7 +61,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor
|
||||
void PowerMonitor::draw_voltage() {
|
||||
const float volts = getVolts();
|
||||
lcd_put_u8str(volts < 100 ? ftostr31ns(volts) : ui16tostr4rj((uint16_t)volts));
|
||||
lcd_put_lchar('V');
|
||||
lcd_put_u8str(F("V"));
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -69,7 +69,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor
|
||||
void PowerMonitor::draw_power() {
|
||||
const float power = getPower();
|
||||
lcd_put_u8str(power < 100 ? ftostr31ns(power) : ui16tostr4rj((uint16_t)power));
|
||||
lcd_put_lchar('W');
|
||||
lcd_put_u8str(F("W"));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@@ -153,6 +153,9 @@ class PrintJobRecovery {
|
||||
static void prepare();
|
||||
|
||||
static void setup() {
|
||||
#if PIN_EXISTS(OUTAGECON)
|
||||
OUT_WRITE(OUTAGECON_PIN, HIGH);
|
||||
#endif
|
||||
#if PIN_EXISTS(POWER_LOSS)
|
||||
#if ENABLED(POWER_LOSS_PULLUP)
|
||||
SET_INPUT_PULLUP(POWER_LOSS_PIN);
|
||||
|
@@ -42,7 +42,7 @@ void Repeat::add_marker(const uint32_t sdpos, const uint16_t count) {
|
||||
SERIAL_ECHO_MSG("!Too many markers.");
|
||||
else {
|
||||
marker[index].sdpos = sdpos;
|
||||
marker[index].counter = count ?: -1;
|
||||
marker[index].counter = count ? count - 1 : -1;
|
||||
index++;
|
||||
DEBUG_ECHOLNPGM("Add Marker ", index, " at ", sdpos, " (", count, ")");
|
||||
}
|
||||
|
@@ -30,9 +30,7 @@
|
||||
|
||||
#include "spindle_laser_types.h"
|
||||
|
||||
#if HAS_BEEPER
|
||||
#include "../libs/buzzer.h"
|
||||
#endif
|
||||
#include "../libs/buzzer.h"
|
||||
|
||||
// Inline laser power
|
||||
#include "../module/planner.h"
|
||||
@@ -285,7 +283,7 @@ public:
|
||||
if (!menuPower) menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP);
|
||||
power = upower_to_ocr(menuPower);
|
||||
apply_power(power);
|
||||
} else
|
||||
} else
|
||||
apply_power(0);
|
||||
}
|
||||
|
||||
|
@@ -112,7 +112,7 @@ void GcodeSuite::M48() {
|
||||
set_bed_leveling_enabled(false);
|
||||
#endif
|
||||
|
||||
TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool()));
|
||||
TERN_(HAS_PTC, ptc.set_enabled(parser.boolval('C', true)));
|
||||
|
||||
// Work with reasonable feedrates
|
||||
remember_feedrate_scaling_off();
|
||||
|
@@ -167,8 +167,6 @@
|
||||
if (parser.seenval('T')) draw_area_max.y = parser.value_linear_units();
|
||||
if (parser.seenval('B')) draw_area_min.y = parser.value_linear_units();
|
||||
if (parser.seenval('H')) polargraph_max_belt_len = parser.value_linear_units();
|
||||
draw_area_size.x = draw_area_max.x - draw_area_min.x;
|
||||
draw_area_size.y = draw_area_max.y - draw_area_min.y;
|
||||
}
|
||||
|
||||
void GcodeSuite::M665_report(const bool forReplay/*=true*/) {
|
||||
|
@@ -43,13 +43,14 @@
|
||||
* S[linear] Swap length
|
||||
* B[linear] Extra Swap resume length
|
||||
* E[linear] Extra Prime length (as used by M217 Q)
|
||||
* P[linear/min] Prime speed
|
||||
* G[linear] Cutting wipe retract length (<=100mm)
|
||||
* R[linear/min] Retract speed
|
||||
* U[linear/min] UnRetract speed
|
||||
* P[linear/min] Prime speed
|
||||
* V[linear] 0/1 Enable auto prime first extruder used
|
||||
* W[linear] 0/1 Enable park & Z Raise
|
||||
* X[linear] Park X (Requires TOOLCHANGE_PARK)
|
||||
* Y[linear] Park Y (Requires TOOLCHANGE_PARK)
|
||||
* Y[linear] Park Y (Requires TOOLCHANGE_PARK and NUM_AXES >= 2)
|
||||
* I[linear] Park I (Requires TOOLCHANGE_PARK and NUM_AXES >= 4)
|
||||
* J[linear] Park J (Requires TOOLCHANGE_PARK and NUM_AXES >= 5)
|
||||
* K[linear] Park K (Requires TOOLCHANGE_PARK and NUM_AXES >= 6)
|
||||
@@ -79,6 +80,7 @@ void GcodeSuite::M217() {
|
||||
if (parser.seenval('B')) { const float v = parser.value_linear_units(); toolchange_settings.extra_resume = constrain(v, -10, 10); }
|
||||
if (parser.seenval('E')) { const float v = parser.value_linear_units(); toolchange_settings.extra_prime = constrain(v, 0, max_extrude); }
|
||||
if (parser.seenval('P')) { const int16_t v = parser.value_linear_units(); toolchange_settings.prime_speed = constrain(v, 10, 5400); }
|
||||
if (parser.seenval('G')) { const int16_t v = parser.value_linear_units(); toolchange_settings.wipe_retract = constrain(v, 0, 100); }
|
||||
if (parser.seenval('R')) { const int16_t v = parser.value_linear_units(); toolchange_settings.retract_speed = constrain(v, 10, 5400); }
|
||||
if (parser.seenval('U')) { const int16_t v = parser.value_linear_units(); toolchange_settings.unretract_speed = constrain(v, 10, 5400); }
|
||||
#if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN
|
||||
@@ -164,21 +166,24 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) {
|
||||
SERIAL_ECHOPGM(" M217");
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
|
||||
SERIAL_ECHOPGM(" S", LINEAR_UNIT(toolchange_settings.swap_length));
|
||||
SERIAL_ECHOPGM_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume),
|
||||
SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime),
|
||||
SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed));
|
||||
SERIAL_ECHOPGM(" R", LINEAR_UNIT(toolchange_settings.retract_speed),
|
||||
" U", LINEAR_UNIT(toolchange_settings.unretract_speed),
|
||||
" F", toolchange_settings.fan_speed,
|
||||
" D", toolchange_settings.fan_time);
|
||||
SERIAL_ECHOPGM_P(
|
||||
PSTR(" S"), LINEAR_UNIT(toolchange_settings.swap_length),
|
||||
SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume),
|
||||
SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime),
|
||||
SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed),
|
||||
PSTR(" G"), LINEAR_UNIT(toolchange_settings.wipe_retract),
|
||||
PSTR(" R"), LINEAR_UNIT(toolchange_settings.retract_speed),
|
||||
PSTR(" U"), LINEAR_UNIT(toolchange_settings.unretract_speed),
|
||||
PSTR(" F"), toolchange_settings.fan_speed,
|
||||
PSTR(" D"), toolchange_settings.fan_time
|
||||
);
|
||||
|
||||
#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
|
||||
SERIAL_ECHOPGM(" A", migration.automode);
|
||||
SERIAL_ECHOPGM(" L", LINEAR_UNIT(migration.last));
|
||||
SERIAL_ECHOPGM(" A", migration.automode, " L", LINEAR_UNIT(migration.last));
|
||||
#endif
|
||||
|
||||
#if ENABLED(TOOLCHANGE_PARK)
|
||||
{
|
||||
SERIAL_ECHOPGM(" W", LINEAR_UNIT(toolchange_settings.enable_park));
|
||||
SERIAL_ECHOPGM_P(
|
||||
SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)
|
||||
@@ -196,6 +201,7 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) {
|
||||
)
|
||||
#endif
|
||||
);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED)
|
||||
|
@@ -57,19 +57,18 @@ void GcodeSuite::M301() {
|
||||
|
||||
if (e < HOTENDS) { // catch bad input value
|
||||
|
||||
if (parser.seenval('P')) PID_PARAM(Kp, e) = parser.value_float();
|
||||
if (parser.seenval('I')) PID_PARAM(Ki, e) = scalePID_i(parser.value_float());
|
||||
if (parser.seenval('D')) PID_PARAM(Kd, e) = scalePID_d(parser.value_float());
|
||||
if (parser.seenval('P')) SET_HOTEND_PID(Kp, e, parser.value_float());
|
||||
if (parser.seenval('I')) SET_HOTEND_PID(Ki, e, parser.value_float());
|
||||
if (parser.seenval('D')) SET_HOTEND_PID(Kd, e, parser.value_float());
|
||||
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
if (parser.seenval('C')) PID_PARAM(Kc, e) = parser.value_float();
|
||||
if (parser.seenval('C')) SET_HOTEND_PID(Kc, e, parser.value_float());
|
||||
if (parser.seenval('L')) thermalManager.lpq_len = parser.value_int();
|
||||
NOMORE(thermalManager.lpq_len, LPQ_MAX_LEN);
|
||||
NOLESS(thermalManager.lpq_len, 0);
|
||||
LIMIT(thermalManager.lpq_len, 0, LPQ_MAX_LEN);
|
||||
#endif
|
||||
|
||||
#if ENABLED(PID_FAN_SCALING)
|
||||
if (parser.seenval('F')) PID_PARAM(Kf, e) = parser.value_float();
|
||||
if (parser.seenval('F')) SET_HOTEND_PID(Kf, e, parser.value_float());
|
||||
#endif
|
||||
|
||||
thermalManager.updatePID();
|
||||
@@ -83,6 +82,7 @@ void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t
|
||||
IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr int8_t eindex = -1);
|
||||
HOTEND_LOOP() {
|
||||
if (e == eindex || eindex == -1) {
|
||||
const hotend_pid_t &pid = thermalManager.temp_hotend[e].pid;
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOPGM_P(
|
||||
#if ENABLED(PID_PARAMS_PER_HOTEND)
|
||||
@@ -90,16 +90,14 @@ void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t
|
||||
#else
|
||||
PSTR(" M301 P")
|
||||
#endif
|
||||
, PID_PARAM(Kp, e)
|
||||
, PSTR(" I"), unscalePID_i(PID_PARAM(Ki, e))
|
||||
, PSTR(" D"), unscalePID_d(PID_PARAM(Kd, e))
|
||||
, pid.p(), PSTR(" I"), pid.i(), PSTR(" D"), pid.d()
|
||||
);
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
SERIAL_ECHOPGM_P(SP_C_STR, PID_PARAM(Kc, e));
|
||||
SERIAL_ECHOPGM_P(SP_C_STR, pid.c());
|
||||
if (e == 0) SERIAL_ECHOPGM(" L", thermalManager.lpq_len);
|
||||
#endif
|
||||
#if ENABLED(PID_FAN_SCALING)
|
||||
SERIAL_ECHOPGM(" F", PID_PARAM(Kf, e));
|
||||
SERIAL_ECHOPGM(" F", pid.f());
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
@@ -36,17 +36,17 @@
|
||||
*/
|
||||
void GcodeSuite::M304() {
|
||||
if (!parser.seen("PID")) return M304_report();
|
||||
if (parser.seenval('P')) thermalManager.temp_bed.pid.Kp = parser.value_float();
|
||||
if (parser.seenval('I')) thermalManager.temp_bed.pid.Ki = scalePID_i(parser.value_float());
|
||||
if (parser.seenval('D')) thermalManager.temp_bed.pid.Kd = scalePID_d(parser.value_float());
|
||||
if (parser.seenval('P')) thermalManager.temp_bed.pid.set_Kp(parser.value_float());
|
||||
if (parser.seenval('I')) thermalManager.temp_bed.pid.set_Ki(parser.value_float());
|
||||
if (parser.seenval('D')) thermalManager.temp_bed.pid.set_Kd(parser.value_float());
|
||||
}
|
||||
|
||||
void GcodeSuite::M304_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, F(STR_BED_PID));
|
||||
SERIAL_ECHOLNPGM(
|
||||
" M304 P", thermalManager.temp_bed.pid.Kp
|
||||
, " I", unscalePID_i(thermalManager.temp_bed.pid.Ki)
|
||||
, " D", unscalePID_d(thermalManager.temp_bed.pid.Kd)
|
||||
SERIAL_ECHOLNPGM(" M304"
|
||||
" P", thermalManager.temp_bed.pid.p()
|
||||
, " I", thermalManager.temp_bed.pid.i()
|
||||
, " D", thermalManager.temp_bed.pid.d()
|
||||
);
|
||||
}
|
||||
|
||||
|
@@ -36,17 +36,17 @@
|
||||
*/
|
||||
void GcodeSuite::M309() {
|
||||
if (!parser.seen("PID")) return M309_report();
|
||||
if (parser.seen('P')) thermalManager.temp_chamber.pid.Kp = parser.value_float();
|
||||
if (parser.seen('I')) thermalManager.temp_chamber.pid.Ki = scalePID_i(parser.value_float());
|
||||
if (parser.seen('D')) thermalManager.temp_chamber.pid.Kd = scalePID_d(parser.value_float());
|
||||
if (parser.seenval('P')) thermalManager.temp_chamber.pid.set_Kp(parser.value_float());
|
||||
if (parser.seenval('I')) thermalManager.temp_chamber.pid.set_Ki(parser.value_float());
|
||||
if (parser.seenval('D')) thermalManager.temp_chamber.pid.set_Kd(parser.value_float());
|
||||
}
|
||||
|
||||
void GcodeSuite::M309_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, F(STR_CHAMBER_PID));
|
||||
SERIAL_ECHOLNPGM(
|
||||
" M309 P", thermalManager.temp_chamber.pid.Kp
|
||||
, " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki)
|
||||
, " D", unscalePID_d(thermalManager.temp_chamber.pid.Kd)
|
||||
SERIAL_ECHOLNPGM(" M309"
|
||||
" P", thermalManager.temp_chamber.pid.p()
|
||||
, " I", thermalManager.temp_chamber.pid.i()
|
||||
, " D", thermalManager.temp_chamber.pid.d()
|
||||
);
|
||||
}
|
||||
|
||||
|
@@ -313,9 +313,16 @@ void GcodeSuite::M43() {
|
||||
|
||||
// 'P' Get the range of pins to test or watch
|
||||
uint8_t first_pin = PARSED_PIN_INDEX('P', 0),
|
||||
last_pin = parser.seenval('P') ? first_pin : TERN(HAS_HIGH_ANALOG_PINS, NUM_DIGITAL_PINS, NUMBER_PINS_TOTAL) - 1;
|
||||
last_pin = parser.seenval('L') ? PARSED_PIN_INDEX('L', 0) : parser.seenval('P') ? first_pin : (NUMBER_PINS_TOTAL) - 1;
|
||||
|
||||
if (first_pin > last_pin) return;
|
||||
NOMORE(first_pin, (NUMBER_PINS_TOTAL) - 1);
|
||||
NOMORE(last_pin, (NUMBER_PINS_TOTAL) - 1);
|
||||
|
||||
if (first_pin > last_pin) {
|
||||
const uint8_t f = first_pin;
|
||||
first_pin = last_pin;
|
||||
last_pin = f;
|
||||
}
|
||||
|
||||
// 'I' to ignore protected pins
|
||||
const bool ignore_protection = parser.boolval('I');
|
||||
|
@@ -22,7 +22,7 @@
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ALL(HAS_SPI_FLASH, SDSUPPORT, MARLIN_DEV_MODE)
|
||||
#if ALL(SPI_FLASH, SDSUPPORT, MARLIN_DEV_MODE)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../sd/cardreader.h"
|
||||
@@ -85,4 +85,4 @@ void GcodeSuite::M994() {
|
||||
card.closefile();
|
||||
}
|
||||
|
||||
#endif // HAS_SPI_FLASH && SDSUPPORT && MARLIN_DEV_MODE
|
||||
#endif // SPI_FLASH && SDSUPPORT && MARLIN_DEV_MODE
|
||||
|
@@ -27,8 +27,8 @@
|
||||
#include "../../gcode.h"
|
||||
#include "../../../module/planner.h"
|
||||
|
||||
#if ENABLED(EXTRA_LIN_ADVANCE_K)
|
||||
float other_extruder_advance_K[EXTRUDERS];
|
||||
#if ENABLED(ADVANCE_K_EXTRA)
|
||||
float other_extruder_advance_K[DISTINCT_E];
|
||||
uint8_t lin_adv_slot = 0;
|
||||
#endif
|
||||
|
||||
@@ -36,8 +36,8 @@
|
||||
* M900: Get or Set Linear Advance K-factor
|
||||
* T<tool> Which tool to address
|
||||
* K<factor> Set current advance K factor (Slot 0).
|
||||
* L<factor> Set secondary advance K factor (Slot 1). Requires EXTRA_LIN_ADVANCE_K.
|
||||
* S<0/1> Activate slot 0 or 1. Requires EXTRA_LIN_ADVANCE_K.
|
||||
* L<factor> Set secondary advance K factor (Slot 1). Requires ADVANCE_K_EXTRA.
|
||||
* S<0/1> Activate slot 0 or 1. Requires ADVANCE_K_EXTRA.
|
||||
*/
|
||||
void GcodeSuite::M900() {
|
||||
|
||||
@@ -50,6 +50,7 @@ void GcodeSuite::M900() {
|
||||
|
||||
#if EXTRUDERS < 2
|
||||
constexpr uint8_t tool_index = 0;
|
||||
UNUSED(tool_index);
|
||||
#else
|
||||
const uint8_t tool_index = parser.intval('T', active_extruder);
|
||||
if (tool_index >= EXTRUDERS) {
|
||||
@@ -58,12 +59,12 @@ void GcodeSuite::M900() {
|
||||
}
|
||||
#endif
|
||||
|
||||
float &kref = planner.extruder_advance_K[tool_index], newK = kref;
|
||||
float &kref = planner.extruder_advance_K[E_INDEX_N(tool_index)], newK = kref;
|
||||
const float oldK = newK;
|
||||
|
||||
#if ENABLED(EXTRA_LIN_ADVANCE_K)
|
||||
#if ENABLED(ADVANCE_K_EXTRA)
|
||||
|
||||
float &lref = other_extruder_advance_K[tool_index];
|
||||
float &lref = other_extruder_advance_K[E_INDEX_N(tool_index)];
|
||||
|
||||
const bool old_slot = TEST(lin_adv_slot, tool_index), // The tool's current slot (0 or 1)
|
||||
new_slot = parser.boolval('S', old_slot); // The passed slot (default = current)
|
||||
@@ -111,9 +112,9 @@ void GcodeSuite::M900() {
|
||||
|
||||
if (!parser.seen_any()) {
|
||||
|
||||
#if ENABLED(EXTRA_LIN_ADVANCE_K)
|
||||
#if ENABLED(ADVANCE_K_EXTRA)
|
||||
|
||||
#if EXTRUDERS < 2
|
||||
#if DISTINCT_E < 2
|
||||
SERIAL_ECHOLNPGM("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")");
|
||||
#else
|
||||
EXTRUDER_LOOP() {
|
||||
@@ -127,7 +128,7 @@ void GcodeSuite::M900() {
|
||||
#else
|
||||
|
||||
SERIAL_ECHO_START();
|
||||
#if EXTRUDERS < 2
|
||||
#if DISTINCT_E < 2
|
||||
SERIAL_ECHOLNPGM("Advance K=", planner.extruder_advance_K[0]);
|
||||
#else
|
||||
SERIAL_ECHOPGM("Advance K");
|
||||
@@ -145,7 +146,7 @@ void GcodeSuite::M900() {
|
||||
|
||||
void GcodeSuite::M900_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, F(STR_LINEAR_ADVANCE));
|
||||
#if EXTRUDERS < 2
|
||||
#if DISTINCT_E < 2
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM(" M900 K", planner.extruder_advance_K[0]);
|
||||
#else
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user