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
|
||||
|
Reference in New Issue
Block a user