🚀 HAL for GD32 MFL (Creality v4.2.2) (#27744)
This commit is contained in:
parent
f6eaca6fcd
commit
78d6fec652
51 changed files with 3873 additions and 16 deletions
3
.github/workflows/ci-build-tests.yml
vendored
3
.github/workflows/ci-build-tests.yml
vendored
|
|
@ -151,6 +151,9 @@ jobs:
|
|||
# HC32
|
||||
- HC32F460C_aquila_101
|
||||
|
||||
# GD32F3
|
||||
- GD32F303RE_creality_mfl
|
||||
|
||||
# LPC176x - Lengthy tests
|
||||
- LPC1768
|
||||
- LPC1769
|
||||
|
|
|
|||
120
Marlin/src/HAL/GD32_MFL/HAL.cpp
Normal file
120
Marlin/src/HAL/GD32_MFL/HAL.cpp
Normal file
|
|
@ -0,0 +1,120 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
uint16_t MarlinHAL::adc_result;
|
||||
|
||||
#if ENABLED(POSTMORTEM_DEBUGGING)
|
||||
extern void install_min_serial();
|
||||
#endif
|
||||
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
// Dump the clock frequencies of the system, AHB, APB1, APB2, and F_CPU.
|
||||
static inline void HAL_clock_frequencies_dump() {
|
||||
auto& rcuInstance = rcu::RCU::get_instance();
|
||||
uint32_t freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_SYS);
|
||||
SERIAL_ECHOPGM("\nSYSTEM_CLOCK=", freq);
|
||||
freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_AHB);
|
||||
SERIAL_ECHOPGM("\nABH_CLOCK=", freq);
|
||||
freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_APB1);
|
||||
SERIAL_ECHOPGM("\nAPB1_CLOCK=", freq);
|
||||
freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_APB2);
|
||||
SERIAL_ECHOPGM("\nAPB2_CLOCK=", freq,
|
||||
"\nF_CPU=", F_CPU);
|
||||
// Done
|
||||
SERIAL_ECHOPGM("\n--\n");
|
||||
}
|
||||
#endif // MARLIN_DEV_MODE
|
||||
|
||||
// Initializes the Marlin HAL
|
||||
void MarlinHAL::init() {
|
||||
constexpr unsigned int cpuFreq = F_CPU;
|
||||
UNUSED(cpuFreq);
|
||||
|
||||
#if PIN_EXISTS(LED)
|
||||
OUT_WRITE(LED_PIN, LOW);
|
||||
#endif
|
||||
|
||||
SetTimerInterruptPriorities();
|
||||
|
||||
// Print clock frequencies to host serial
|
||||
TERN_(MARLIN_DEV_MODE, HAL_clock_frequencies_dump());
|
||||
|
||||
// Register min serial
|
||||
TERN_(POSTMORTEM_DEBUGGING, install_min_serial());
|
||||
}
|
||||
|
||||
// Returns the reset source based on the flags set in the RCU module
|
||||
uint8_t MarlinHAL::get_reset_source() {
|
||||
return
|
||||
(RCU_I.get_flag(rcu::Status_Flags::FLAG_FWDGTRST)) ? RST_WATCHDOG :
|
||||
(RCU_I.get_flag(rcu::Status_Flags::FLAG_SWRST)) ? RST_SOFTWARE :
|
||||
(RCU_I.get_flag(rcu::Status_Flags::FLAG_EPRST)) ? RST_EXTERNAL :
|
||||
(RCU_I.get_flag(rcu::Status_Flags::FLAG_PORRST)) ? RST_POWER_ON :
|
||||
(RCU_I.get_flag(rcu::Status_Flags::FLAG_LPRST)) ? RST_BROWN_OUT :
|
||||
0;
|
||||
}
|
||||
|
||||
// Returns the amount of free memory available in bytes
|
||||
int MarlinHAL::freeMemory() {
|
||||
volatile char top;
|
||||
return &top - reinterpret_cast<char*>(_sbrk(0));
|
||||
}
|
||||
|
||||
// Watchdog Timer
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
|
||||
|
||||
#include <FWatchdogTimer.h>
|
||||
|
||||
FWatchdogTimer& watchdogTimer = FWatchdogTimer::get_instance();
|
||||
|
||||
// Initializes the watchdog timer
|
||||
void MarlinHAL::watchdog_init() {
|
||||
IF_DISABLED(DISABLE_WATCHDOG_INIT, watchdogTimer.begin(WDT_TIMEOUT_US));
|
||||
}
|
||||
|
||||
// Refreshes the watchdog timer to prevent system reset
|
||||
void MarlinHAL::watchdog_refresh() {
|
||||
watchdogTimer.reload();
|
||||
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
|
||||
TOGGLE(LED_PIN); // Heartbeat indicator
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
extern "C" {
|
||||
extern unsigned int _ebss; // End of bss section
|
||||
}
|
||||
|
||||
// Resets the system to initiate a firmware flash.
|
||||
WEAK void flashFirmware(const int16_t) {
|
||||
hal.reboot();
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
158
Marlin/src/HAL/GD32_MFL/HAL.h
Normal file
158
Marlin/src/HAL/GD32_MFL/HAL.h
Normal file
|
|
@ -0,0 +1,158 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#define CPU_32_BIT
|
||||
|
||||
#include "../../core/macros.h"
|
||||
#include "../shared/Marduino.h"
|
||||
#include "../shared/math_32bit.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
|
||||
#include "temp_soc.h"
|
||||
#include "fastio.h"
|
||||
#include "Servo.h"
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#include <stdint.h>
|
||||
#include <GPIO.hpp>
|
||||
#include <AFIO.hpp>
|
||||
|
||||
// Default graphical display delays
|
||||
#define CPU_ST7920_DELAY_1 300
|
||||
#define CPU_ST7920_DELAY_2 40
|
||||
#define CPU_ST7920_DELAY_3 340
|
||||
|
||||
// Serial Ports
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
// Interrupts
|
||||
#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
|
||||
#define CRITICAL_SECTION_END() if (irqon) __enable_irq()
|
||||
|
||||
#define cli() __disable_irq()
|
||||
#define sei() __enable_irq()
|
||||
|
||||
// Alias of __bss_end__
|
||||
#define __bss_end __bss_end__
|
||||
|
||||
// Types
|
||||
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
|
||||
typedef uint8_t pin_t; // Parity with mfl platform
|
||||
|
||||
// Servo
|
||||
class libServo;
|
||||
typedef libServo hal_servo_t;
|
||||
#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
|
||||
#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
|
||||
|
||||
// Debugging
|
||||
#define JTAG_DISABLE() AFIO_I.set_remap(gpio::Pin_Remap_Select::SWJ_DP_ONLY_REMAP)
|
||||
#define JTAGSWD_DISABLE() AFIO_I.set_remap(gpio::Pin_Remap_Select::SWJ_ALL_DISABLED_REMAP)
|
||||
#define JTAGSWD_RESET() AFIO_I.set_remap(gpio::Pin_Remap_Select::FULL_SWJ_REMAP)
|
||||
|
||||
// ADC
|
||||
#ifdef ADC_RESOLUTION
|
||||
#define HAL_ADC_RESOLUTION ADC_RESOLUTION
|
||||
#else
|
||||
#define HAL_ADC_RESOLUTION 12
|
||||
#endif
|
||||
|
||||
#define HAL_ADC_VREF_MV 3300
|
||||
|
||||
// Disable Marlin's software oversampling.
|
||||
// The MFL framework uses 16x hardware oversampling by default
|
||||
#define HAL_ADC_FILTERED
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
#ifndef PLATFORM_M997_SUPPORT
|
||||
#define PLATFORM_M997_SUPPORT
|
||||
#endif
|
||||
|
||||
void flashFirmware(const int16_t);
|
||||
|
||||
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
|
||||
|
||||
extern "C" char* _sbrk(int incr);
|
||||
extern "C" char* dtostrf(double val, signed char width, unsigned char prec, char* sout);
|
||||
|
||||
// MarlinHAL Class
|
||||
class MarlinHAL {
|
||||
public:
|
||||
// Before setup()
|
||||
MarlinHAL() {}
|
||||
|
||||
// Watchdog
|
||||
static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {});
|
||||
static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
|
||||
|
||||
static void init(); // called early in setup()
|
||||
static void init_board() {} // called less early in setup()
|
||||
static void reboot() { NVIC_SystemReset(); } // restart the firmware from 0x0
|
||||
|
||||
// Interrupts
|
||||
static bool isr_state() { return !__get_PRIMASK(); }
|
||||
static void isr_on() { sei(); }
|
||||
static void isr_off() { cli(); }
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks called from idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
static uint8_t get_reset_source();
|
||||
static void clear_reset_source() { RCU_I.clear_all_reset_flags(); }
|
||||
|
||||
// Free SRAM
|
||||
static int freeMemory();
|
||||
|
||||
// ADC methods
|
||||
static uint16_t adc_result;
|
||||
|
||||
// Called by Temperature::init once at startup
|
||||
static void adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); }
|
||||
|
||||
// Called by Temperature::init for each sensor at startup
|
||||
static void adc_enable(const pin_t pin) { pinMode(pin, INPUT); }
|
||||
|
||||
// Called from Temperature::isr to start ADC sampling on the given pin
|
||||
static void adc_start(const pin_t pin) { adc_result = static_cast<uint16_t>(analogRead(pin)); }
|
||||
|
||||
// Check if ADC is ready for reading
|
||||
static bool adc_ready() { return true; }
|
||||
|
||||
// Current value of the ADC register
|
||||
static uint16_t adc_value() { return adc_result; }
|
||||
|
||||
// Set the PWM duty cycle for the pin to the given value.
|
||||
// Optionally invert the duty cycle [default = false]
|
||||
// Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
|
||||
static void set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale = 255U, const bool invert = false);
|
||||
|
||||
// Set the frequency of the timer for the given pin.
|
||||
// All Timer PWM pins run at the same frequency.
|
||||
static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
|
||||
};
|
||||
26
Marlin/src/HAL/GD32_MFL/MarlinSPI.h
Normal file
26
Marlin/src/HAL/GD32_MFL/MarlinSPI.h
Normal file
|
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <SPI.h>
|
||||
|
||||
using MarlinSPI = SPIClass;
|
||||
101
Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp
Normal file
101
Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp
Normal file
|
|
@ -0,0 +1,101 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/e_parser.h"
|
||||
#endif
|
||||
|
||||
using namespace arduino;
|
||||
|
||||
MarlinSerial& MarlinSerial::get_instance(usart::USART_Base Base, pin_size_t rxPin, pin_size_t txPin) {
|
||||
UsartSerial& serial = UsartSerial::get_instance(Base, rxPin, txPin);
|
||||
return *reinterpret_cast<MarlinSerial*>(&serial);
|
||||
}
|
||||
|
||||
#if USING_HW_SERIAL0
|
||||
MSerialT MSerial0(true, MarlinSerial::get_instance(usart::USART_Base::USART0_BASE, NO_PIN, NO_PIN));
|
||||
#endif
|
||||
#if USING_HW_SERIAL1
|
||||
MSerialT MSerial1(true, MarlinSerial::get_instance(usart::USART_Base::USART1_BASE, NO_PIN, NO_PIN));
|
||||
#endif
|
||||
#if USING_HW_SERIAL2
|
||||
MSerialT MSerial2(true, MarlinSerial::get_instance(usart::USART_Base::USART2_BASE, NO_PIN, NO_PIN));
|
||||
#endif
|
||||
#if USING_HW_SERIAL3
|
||||
MSerialT MSerial3(true, MarlinSerial::get_instance(usart::USART_Base::UART3_BASE, NO_PIN, NO_PIN));
|
||||
#endif
|
||||
#if USING_HW_SERIAL4
|
||||
MSerialT MSerial4(true, MarlinSerial::get_instance(usart::USART_Base::UART4_BASE, NO_PIN, NO_PIN));
|
||||
#endif
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
// This callback needs to access the specific MarlinSerial instance
|
||||
// We'll use a static pointer to track the current instance
|
||||
static MarlinSerial* current_serial_instance = nullptr;
|
||||
|
||||
static void emergency_callback() {
|
||||
if (current_serial_instance) {
|
||||
uint8_t last_data = current_serial_instance->get_last_data();
|
||||
emergency_parser.update(current_serial_instance->emergency_state, last_data);
|
||||
}
|
||||
}
|
||||
|
||||
void MarlinSerial::register_emergency_callback(void (*callback)()) {
|
||||
usart_.register_interrupt_callback(usart::Interrupt_Type::INTR_RBNEIE, callback);
|
||||
}
|
||||
#endif
|
||||
|
||||
void MarlinSerial::begin(unsigned long baudrate, uint16_t config) {
|
||||
UsartSerial::begin(baudrate, config);
|
||||
#if DISABLED(SERIAL_DMA)
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
current_serial_instance = this;
|
||||
register_emergency_callback(emergency_callback);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void MarlinSerial::updateRxDmaBuffer() {
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
// Get the number of bytes available in the receive buffer
|
||||
size_t available_bytes = usart_.available_for_read(true);
|
||||
uint8_t data;
|
||||
|
||||
// Process only the available data
|
||||
for (size_t i = 0; i < available_bytes; ++i) {
|
||||
if (usart_.read_rx_buffer(data)) {
|
||||
emergency_parser.update(emergency_state, data);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
// Call the base class implementation to handle any additional updates
|
||||
UsartSerial::updateRxDmaBuffer();
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
75
Marlin/src/HAL/GD32_MFL/MarlinSerial.h
Normal file
75
Marlin/src/HAL/GD32_MFL/MarlinSerial.h
Normal file
|
|
@ -0,0 +1,75 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/e_parser.h"
|
||||
#endif
|
||||
|
||||
#include <UsartSerial.hpp>
|
||||
|
||||
#include "../../core/serial_hook.h"
|
||||
|
||||
#define SERIAL_INDEX_MIN 0
|
||||
#define SERIAL_INDEX_MAX 4
|
||||
|
||||
#include "../shared/serial_ports.h"
|
||||
|
||||
#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI)
|
||||
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
|
||||
#endif
|
||||
|
||||
using namespace arduino;
|
||||
|
||||
struct MarlinSerial : public UsartSerial {
|
||||
static MarlinSerial& get_instance(usart::USART_Base Base, pin_size_t rxPin = NO_PIN, pin_size_t txPin = NO_PIN);
|
||||
|
||||
void begin(unsigned long baudrate, uint16_t config);
|
||||
inline void begin(unsigned long baudrate) { begin(baudrate, SERIAL_8N1); }
|
||||
void updateRxDmaBuffer();
|
||||
|
||||
#if DISABLED(SERIAL_DMA)
|
||||
FORCE_INLINE static uint8_t buffer_overruns() { return 0; }
|
||||
#endif
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
EmergencyParser::State emergency_state;
|
||||
|
||||
// Accessor method to get the last received byte
|
||||
uint8_t get_last_data() { return usart_.get_last_data(); }
|
||||
|
||||
// Register the emergency callback
|
||||
void register_emergency_callback(void (*callback)());
|
||||
#endif
|
||||
|
||||
protected:
|
||||
using UsartSerial::UsartSerial;
|
||||
};
|
||||
|
||||
typedef Serial1Class<MarlinSerial> MSerialT;
|
||||
extern MSerialT MSerial0;
|
||||
extern MSerialT MSerial1;
|
||||
extern MSerialT MSerial2;
|
||||
extern MSerialT MSerial3;
|
||||
extern MSerialT MSerial4;
|
||||
163
Marlin/src/HAL/GD32_MFL/MinSerial.cpp
Normal file
163
Marlin/src/HAL/GD32_MFL/MinSerial.cpp
Normal file
|
|
@ -0,0 +1,163 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(POSTMORTEM_DEBUGGING)
|
||||
#include "../shared/MinSerial.h"
|
||||
|
||||
// Base addresses for USART peripherals
|
||||
static constexpr uintptr_t USART_base[] = {
|
||||
0x40013800, // USART0
|
||||
0x40004400, // USART1
|
||||
0x40004800, // USART2
|
||||
0x40004C00, // UART3
|
||||
0x40005000 // UART4
|
||||
};
|
||||
|
||||
// Register offsets
|
||||
static constexpr uint32_t STAT0_OFFSET = 0x00U;
|
||||
static constexpr uint32_t DATA_OFFSET = 0x04U;
|
||||
static constexpr uint32_t BAUD_OFFSET = 0x08U;
|
||||
static constexpr uint32_t CTL0_OFFSET = 0x0CU;
|
||||
static constexpr uint32_t CTL1_OFFSET = 0x14U;
|
||||
|
||||
// Bit positions
|
||||
static constexpr uint32_t TBE_BIT = 7;
|
||||
static constexpr uint32_t TEN_BIT = 3;
|
||||
static constexpr uint32_t UEN_BIT = 13;
|
||||
|
||||
// NVIC interrupt numbers for USART
|
||||
static constexpr int nvicUART[] = { 37, 38, 39, 52, 53 };
|
||||
|
||||
// RCU PCLK values for USART
|
||||
static constexpr rcu::RCU_PCLK clockRegs[] = {
|
||||
rcu::RCU_PCLK::PCLK_USART0,
|
||||
rcu::RCU_PCLK::PCLK_USART1,
|
||||
rcu::RCU_PCLK::PCLK_USART2,
|
||||
rcu::RCU_PCLK::PCLK_UART3,
|
||||
rcu::RCU_PCLK::PCLK_UART4
|
||||
};
|
||||
|
||||
// Memory barrier instructions
|
||||
#define isb() __asm__ __volatile__ ("isb" : : : "memory")
|
||||
#define dsb() __asm__ __volatile__ ("dsb" : : : "memory")
|
||||
#define sw_barrier() __asm__ volatile("" : : : "memory")
|
||||
|
||||
// Direct register access macros
|
||||
#define USART_REG(offset) (*(volatile uint32_t*)(USART_base[SERIAL_PORT] + (offset)))
|
||||
#define USART_STAT0 USART_REG(STAT0_OFFSET)
|
||||
#define USART_DATA USART_REG(DATA_OFFSET)
|
||||
#define USART_BAUD USART_REG(BAUD_OFFSET)
|
||||
#define USART_CTL0 USART_REG(CTL0_OFFSET)
|
||||
#define USART_CTL1 USART_REG(CTL1_OFFSET)
|
||||
|
||||
// Bit manipulation macros
|
||||
#define READ_BIT(reg, bit) (((reg) >> (bit)) & 1U)
|
||||
#define SET_BIT(reg, bit) ((reg) |= (1U << (bit)))
|
||||
#define CLEAR_BIT(reg, bit) ((reg) &= ~(1U << (bit)))
|
||||
|
||||
// Initializes the MinSerial interface.
|
||||
// This function sets up the USART interface for serial communication.
|
||||
// If the selected serial port is not a hardware port, it disables the severe error reporting feature.
|
||||
static void MinSerialBegin() {
|
||||
#if !WITHIN(SERIAL_PORT, 0, 4)
|
||||
#warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error."
|
||||
#warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port."
|
||||
#else
|
||||
int nvicIndex = nvicUART[SERIAL_PORT];
|
||||
|
||||
// NVIC base address for interrupt disable
|
||||
struct NVICMin {
|
||||
volatile uint32_t ISER[32];
|
||||
volatile uint32_t ICER[32];
|
||||
};
|
||||
NVICMin *nvicBase = (NVICMin*)0xE000E100;
|
||||
|
||||
SBI32(nvicBase->ICER[nvicIndex >> 5], nvicIndex & 0x1F);
|
||||
|
||||
// We require memory barriers to properly disable interrupts
|
||||
// (https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the)
|
||||
dsb();
|
||||
isb();
|
||||
|
||||
// Get the RCU PCLK for this USART
|
||||
rcu::RCU_PCLK pclk = clockRegs[SERIAL_PORT];
|
||||
|
||||
// Disable then enable usart peripheral clocks
|
||||
rcu::RCU_DEVICE.set_pclk_enable(pclk, false);
|
||||
rcu::RCU_DEVICE.set_pclk_enable(pclk, true);
|
||||
|
||||
// Save current baudrate
|
||||
uint32_t baudrate = USART_BAUD;
|
||||
|
||||
// Reset USART control registers
|
||||
USART_CTL0 = 0;
|
||||
USART_CTL1 = 0; // 1 stop bit
|
||||
|
||||
// Restore baudrate
|
||||
USART_BAUD = baudrate;
|
||||
|
||||
// Enable transmitter and USART (8 bits, no parity, 1 stop bit)
|
||||
SET_BIT(USART_CTL0, TEN_BIT);
|
||||
SET_BIT(USART_CTL0, UEN_BIT);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Writes a single character to the serial port.
|
||||
static void MinSerialWrite(char c) {
|
||||
#if WITHIN(SERIAL_PORT, 0, 4)
|
||||
// Wait until transmit buffer is empty
|
||||
while (!READ_BIT(USART_STAT0, TBE_BIT)) {
|
||||
hal.watchdog_refresh();
|
||||
sw_barrier();
|
||||
}
|
||||
// Write character to data register
|
||||
USART_DATA = c;
|
||||
#endif
|
||||
}
|
||||
|
||||
// Installs the minimum serial interface.
|
||||
// Sets the HAL_min_serial_init and HAL_min_serial_out function pointers to MinSerialBegin and MinSerialWrite respectively.
|
||||
void install_min_serial() {
|
||||
HAL_min_serial_init = &MinSerialBegin;
|
||||
HAL_min_serial_out = &MinSerialWrite;
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
// A low-level assembly-based jump handler.
|
||||
// Unconditionally branches to the CommonHandler_ASM function.
|
||||
__attribute__((naked, aligned(4))) void JumpHandler_ASM() {
|
||||
__asm__ __volatile__ ("b CommonHandler_ASM\n");
|
||||
}
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler();
|
||||
}
|
||||
|
||||
#endif // POSTMORTEM_DEBUGGING
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
8
Marlin/src/HAL/GD32_MFL/README.md
Normal file
8
Marlin/src/HAL/GD32_MFL/README.md
Normal file
|
|
@ -0,0 +1,8 @@
|
|||
# Generic GD32 HAL based on the MFL Arduino Core
|
||||
|
||||
This HAL is eventually intended to act as the generic HAL for all GD32 chips using the MFL library.
|
||||
|
||||
Currently it supports:
|
||||
* GD32F303RET6
|
||||
|
||||
Targeting the official [MFL Arduino Core](https://github.com/bnmguy/ArduinoCore_MFL).
|
||||
1022
Marlin/src/HAL/GD32_MFL/SDCard.cpp
Normal file
1022
Marlin/src/HAL/GD32_MFL/SDCard.cpp
Normal file
File diff suppressed because it is too large
Load diff
214
Marlin/src/HAL/GD32_MFL/SDCard.h
Normal file
214
Marlin/src/HAL/GD32_MFL/SDCard.h
Normal file
|
|
@ -0,0 +1,214 @@
|
|||
//
|
||||
// MFL gd32f30x SDCARD using DMA through SDIO in C++
|
||||
//
|
||||
// Copyright (C) 2025 B. Mourit <bnmguy@gmail.com>
|
||||
//
|
||||
// This software is free software: you can redistribute it and/or modify it under the terms of the
|
||||
// GNU Lesser General Public License as published by the Free Software Foundation,
|
||||
// either version 3 of the License, or (at your option) any later version.
|
||||
//
|
||||
// This software is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
|
||||
// without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
// See the GNU Lesser General Public License for more details.
|
||||
//
|
||||
// You should have received a copy of the GNU Lesser General Public License along with this software.
|
||||
// If not, see <https://www.gnu.org/licenses/>.
|
||||
//
|
||||
#pragma once
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include "SDIO.hpp"
|
||||
|
||||
namespace sdio {
|
||||
|
||||
class DMA;
|
||||
|
||||
class CardDMA {
|
||||
public:
|
||||
static CardDMA& get_instance();
|
||||
|
||||
SDIO_Error_Type init();
|
||||
SDIO_Error_Type card_init();
|
||||
SDIO_Error_Type begin_startup_procedure();
|
||||
void begin_shutdown_procedure();
|
||||
// Configuration
|
||||
SDIO_Error_Type set_hardware_bus_width(Bus_Width width);
|
||||
// Main read/write functions for single and multiblock transfers
|
||||
SDIO_Error_Type read(uint8_t* buf, uint32_t address, uint32_t count);
|
||||
SDIO_Error_Type write(uint8_t* buf, uint32_t address, uint32_t count);
|
||||
// DMA transfers
|
||||
// Other card functions
|
||||
SDIO_Error_Type erase(uint32_t address_start, uint32_t address_end);
|
||||
// Interrupt handler
|
||||
void handle_interrupts();
|
||||
// Card select
|
||||
SDIO_Error_Type select_deselect();
|
||||
|
||||
SDIO_Error_Type get_card_interface_status(uint32_t* status);
|
||||
SDIO_Error_Type get_sdcard_status(uint32_t* status);
|
||||
|
||||
void check_dma_complete();
|
||||
SDIO_Error_Type stop_transfer();
|
||||
|
||||
Transfer_State get_transfer_state();
|
||||
uint32_t get_card_capacity() const;
|
||||
|
||||
SDIO_Error_Type send_bus_width_command(uint32_t width_value);
|
||||
|
||||
SDIO_Error_Type get_card_specific_data(Card_Info* info);
|
||||
constexpr Block_Size get_data_block_size_index(uint16_t size);
|
||||
|
||||
SDIO_Error_Type get_card_state(Card_State* card_state);
|
||||
SDIO_Error_Type check_sdio_status(Command_Index index = Command_Index::INVALID, bool check_index = false, bool ignore_crc = false);
|
||||
|
||||
// DMA configuration
|
||||
void set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write);
|
||||
|
||||
// SDIO configuration
|
||||
void sdio_configure(const SDIO_Config config) { sdio_.init(config); }
|
||||
|
||||
// Varaible stored parameters
|
||||
SDIO_Error_Type get_scr(uint16_t rca, uint32_t* scr);
|
||||
SDIO_Error_Type store_cid();
|
||||
SDIO_Error_Type store_csd();
|
||||
|
||||
// Accessor methods
|
||||
SDIO_Config& get_config() { return config_; }
|
||||
dma::DMA& get_dma_instance() { return dma_; }
|
||||
void set_data_end_interrupt() { sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, true); }
|
||||
void set_sdio_dma_enable(bool enable) { sdio_.set_dma_enable(enable); }
|
||||
bool get_is_sdio_rx() { return is_rx_; }
|
||||
void clear_sdio_data_flags() { sdio_.clear_multiple_interrupt_flags(clear_data_flags); }
|
||||
void clear_sdio_cmd_flags() { sdio_.clear_multiple_interrupt_flags(clear_command_flags); }
|
||||
void clear_sdio_common_flags() { sdio_.clear_multiple_interrupt_flags(clear_common_flags); }
|
||||
Operational_State get_state() { return current_state_; }
|
||||
void set_state(Operational_State state) { current_state_ = state; }
|
||||
void set_transfer_end(bool value) { transfer_end_ = value; }
|
||||
void set_transfer_error(SDIO_Error_Type error) { transfer_error_ = error; }
|
||||
|
||||
inline SDIO_Error_Type set_desired_clock(uint32_t desired_clock, bool wide_bus, bool low_power) {
|
||||
sdio_.init({
|
||||
desired_clock,
|
||||
Clock_Edge::RISING_EDGE,
|
||||
wide_bus ? Bus_Width::WIDTH_4BIT : Bus_Width::WIDTH_1BIT,
|
||||
false,
|
||||
low_power,
|
||||
false
|
||||
});
|
||||
sync_domains();
|
||||
desired_clock_ = desired_clock;
|
||||
|
||||
return SDIO_Error_Type::OK;
|
||||
}
|
||||
|
||||
private:
|
||||
CardDMA();
|
||||
|
||||
// Prevent copying or assigning
|
||||
CardDMA(const CardDMA&) = delete;
|
||||
CardDMA& operator=(const CardDMA&) = delete;
|
||||
|
||||
// Helper function
|
||||
SDIO_Error_Type wait_for_card_ready();
|
||||
|
||||
// Member variables
|
||||
alignas(4) uint32_t sdcard_csd_[4];
|
||||
alignas(4) uint32_t sdcard_cid_[4];
|
||||
alignas(4) uint32_t sdcard_scr_[2];
|
||||
uint32_t desired_clock_;
|
||||
uint32_t stop_condition_;
|
||||
uint32_t total_bytes_;
|
||||
uint32_t count_;
|
||||
SDIO& sdio_;
|
||||
SDIO_Config& config_;
|
||||
const dma::DMA_Base dmaBase_;
|
||||
const dma::DMA_Channel dmaChannel_;
|
||||
dma::DMA& dma_;
|
||||
uint16_t sdcard_rca_;
|
||||
SDIO_Error_Type transfer_error_;
|
||||
Interface_Version interface_version_;
|
||||
Card_Type card_type_;
|
||||
volatile bool transfer_end_;
|
||||
volatile bool is_rx_;
|
||||
volatile bool multiblock_;
|
||||
volatile Operational_State current_state_;
|
||||
|
||||
// Private helper methods
|
||||
SDIO_Error_Type validate_voltage();
|
||||
SDIO_Error_Type get_r1_result(Command_Index index);
|
||||
//SDIO_Error_Type get_r2_r3_result();
|
||||
SDIO_Error_Type get_r6_result(Command_Index index, uint16_t* rca);
|
||||
SDIO_Error_Type get_r7_result();
|
||||
//SDIO_Error_Type get_r1_error_type(uint32_t response);
|
||||
SDIO_Error_Type get_command_sent_result();
|
||||
|
||||
inline void sync_domains() {
|
||||
delayMicroseconds(8);
|
||||
}
|
||||
|
||||
inline bool validate_transfer_params(uint32_t* buf, uint16_t size) {
|
||||
if (buf == nullptr) return false;
|
||||
// Size must be > 0, <= 2048 and power of 2
|
||||
if ((size == 0U) || (size > 2048U) || (size & (size - 1U))) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void process_sdsc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) {
|
||||
info->csd.device_size = (static_cast<uint32_t>(csd_bytes[6] & 0x03U) << 10U) |
|
||||
(static_cast<uint32_t>(csd_bytes[7]) << 2U) |
|
||||
(static_cast<uint32_t>((csd_bytes[8] & 0xC0U) >> 6U));
|
||||
info->csd.device_size_multiplier = static_cast<uint8_t>((csd_bytes[9] & 0x03U) << 1U |
|
||||
(csd_bytes[10] & 0x80U) >> 7U);
|
||||
|
||||
info->block_size = static_cast<uint32_t>(1 << info->csd.read_block_length);
|
||||
info->capacity = static_cast<uint32_t>((info->csd.device_size + 1U) *
|
||||
(1U << (info->csd.device_size_multiplier + 2U)) *
|
||||
info->block_size);
|
||||
}
|
||||
|
||||
void process_sdhc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) {
|
||||
info->csd.device_size = static_cast<uint32_t>((csd_bytes[7] & 0x3FU) << 16U) |
|
||||
static_cast<uint32_t>((csd_bytes[8]) << 8U) |
|
||||
static_cast<uint32_t>(csd_bytes[9]);
|
||||
|
||||
info->block_size = BLOCK_SIZE;
|
||||
info->capacity = static_cast<uint32_t>((info->csd.device_size + 1U) *
|
||||
BLOCK_SIZE * KILOBYTE);
|
||||
}
|
||||
|
||||
void process_common_csd_tail(Card_Info* info, const uint8_t* csd_bytes) {
|
||||
info->csd.sector_size = static_cast<uint8_t>(((csd_bytes[9] & 0x3FU) << 1U) |
|
||||
(csd_bytes[10] & 0x80U) >> 7U);
|
||||
info->csd.speed_factor = static_cast<uint8_t>((csd_bytes[11] & 0x1CU) >> 2U);
|
||||
info->csd.write_block_length = static_cast<uint8_t>(((csd_bytes[11] & 0x03U) << 2U) |
|
||||
((csd_bytes[12] & 0xC0U) >> 6U));
|
||||
info->csd.checksum = static_cast<uint8_t>((csd_bytes[15] & 0xFEU) >> 1U);
|
||||
}
|
||||
|
||||
inline void disable_all_interrupts() {
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::STBITEIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::TFHIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::RFHIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::TXUREIE, false);
|
||||
sdio_.set_interrupt_enable(Interrupt_Type::RXOREIE, false);
|
||||
}
|
||||
|
||||
template <typename CheckFunc>
|
||||
inline SDIO_Error_Type send_command_and_check(Command_Index command, uint32_t argument,
|
||||
Command_Response response, Wait_Type type, CheckFunc check_result) {
|
||||
sdio_.set_command_state_machine(command, argument, response, type);
|
||||
sync_domains();
|
||||
sdio_.set_command_state_machine_enable(true);
|
||||
return check_result();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace sdio
|
||||
|
||||
extern sdio::CardDMA& CardDMA_I;
|
||||
122
Marlin/src/HAL/GD32_MFL/Servo.cpp
Normal file
122
Marlin/src/HAL/GD32_MFL/Servo.cpp
Normal file
|
|
@ -0,0 +1,122 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS
|
||||
|
||||
#include "Servo.h"
|
||||
|
||||
static uint_fast8_t servoCount = 0;
|
||||
static libServo* servos[NUM_SERVOS] = {0};
|
||||
constexpr millis_t servoDelay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
|
||||
// Initialize to the default timer priority. This will be overridden by a call from timers.cpp.
|
||||
// This allows all timer interrupt priorities to be managed from a single location in the HAL.
|
||||
static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 12, 0);
|
||||
|
||||
// This must be called after the MFL Servo class has initialized the timer.
|
||||
// To be safe this is currently called after every call to attach().
|
||||
static void fixServoTimerInterruptPriority() {
|
||||
NVIC_SetPriority(getTimerUpIRQ(TIMER_SERVO), servo_interrupt_priority);
|
||||
}
|
||||
|
||||
// Default constructor for libServo class.
|
||||
// Initializes the servo delay, pause state, and pause value.
|
||||
// Registers the servo instance in the servos array.
|
||||
libServo::libServo() : delay(servoDelay[servoCount]),
|
||||
was_attached_before_pause(false),
|
||||
value_before_pause(0) {
|
||||
servos[servoCount++] = this;
|
||||
}
|
||||
|
||||
// Attaches a servo to a specified pin.
|
||||
int8_t libServo::attach(const int pin) {
|
||||
if (servoCount >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servo_pin = pin;
|
||||
auto result = mflServo.attach(servo_pin);
|
||||
fixServoTimerInterruptPriority();
|
||||
return result;
|
||||
}
|
||||
|
||||
// Attaches a servo to a specified pin with minimum and maximum pulse widths.
|
||||
int8_t libServo::attach(const int pin, const int min, const int max) {
|
||||
if (servoCount >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servo_pin = pin;
|
||||
auto result = mflServo.attach(servo_pin, min, max);
|
||||
fixServoTimerInterruptPriority();
|
||||
return result;
|
||||
}
|
||||
|
||||
// Moves the servo to a specified position.
|
||||
void libServo::move(const int value) {
|
||||
if (attach(0) >= 0) {
|
||||
mflServo.write(value);
|
||||
safe_delay(delay);
|
||||
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
|
||||
}
|
||||
}
|
||||
|
||||
// Pause the servo by detaching it and storing its current state.
|
||||
void libServo::pause() {
|
||||
was_attached_before_pause = mflServo.attached();
|
||||
if (was_attached_before_pause) {
|
||||
value_before_pause = mflServo.read();
|
||||
mflServo.detach();
|
||||
}
|
||||
}
|
||||
|
||||
// Resume a previously paused servo.
|
||||
// If the servo was attached before the pause, this function re-attaches
|
||||
// the servo and moves it to the position it was in before the pause.
|
||||
void libServo::resume() {
|
||||
if (was_attached_before_pause) {
|
||||
attach();
|
||||
move(value_before_pause);
|
||||
}
|
||||
}
|
||||
|
||||
// Pause all servos by stopping their timers.
|
||||
void libServo::pause_all_servos() {
|
||||
for (auto& servo : servos)
|
||||
if (servo) servo->pause();
|
||||
}
|
||||
|
||||
// Resume all paused servos by starting their timers.
|
||||
void libServo::resume_all_servos() {
|
||||
for (auto& servo : servos)
|
||||
if (servo) servo->resume();
|
||||
}
|
||||
|
||||
// Set the interrupt priority for the servo.
|
||||
// @param preemptPriority The preempt priority level.
|
||||
// @param subPriority The sub priority level.
|
||||
void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
|
||||
servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
|
||||
}
|
||||
|
||||
#endif // HAS_SERVOS
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
56
Marlin/src/HAL/GD32_MFL/Servo.h
Normal file
56
Marlin/src/HAL/GD32_MFL/Servo.h
Normal file
|
|
@ -0,0 +1,56 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <Servo.h>
|
||||
|
||||
#include "../../core/millis_t.h"
|
||||
|
||||
// Inherit and expand on the official library
|
||||
class libServo {
|
||||
public:
|
||||
libServo();
|
||||
|
||||
int8_t attach(const int pin = 0); // pin == 0 uses value from previous call
|
||||
int8_t attach(const int pin, const int min, const int max);
|
||||
void detach() { mflServo.detach(); }
|
||||
|
||||
int read() { return mflServo.read(); }
|
||||
void move(const int value);
|
||||
|
||||
void pause();
|
||||
void resume();
|
||||
|
||||
static void pause_all_servos();
|
||||
static void resume_all_servos();
|
||||
|
||||
static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
|
||||
|
||||
private:
|
||||
Servo mflServo;
|
||||
|
||||
int servoPin = 0;
|
||||
millis_t delay = 0;
|
||||
|
||||
bool was_attached_before_pause;
|
||||
int value_before_pause;
|
||||
};
|
||||
129
Marlin/src/HAL/GD32_MFL/dogm/u8g_com_mfl_swspi.cpp
Normal file
129
Marlin/src/HAL/GD32_MFL/dogm/u8g_com_mfl_swspi.cpp
Normal file
|
|
@ -0,0 +1,129 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm / Ryan Power
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
|
||||
|
||||
#include <U8glib-HAL.h>
|
||||
#include "../../shared/HAL_SPI.h"
|
||||
|
||||
#define nop asm volatile ("\tnop\n")
|
||||
|
||||
static inline uint8_t swSpiTransfer_mode_0(uint8_t b) {
|
||||
for (uint8_t i = 0; i < 8; ++i) {
|
||||
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
||||
WRITE(DOGLCD_SCK, HIGH);
|
||||
WRITE(DOGLCD_MOSI, state);
|
||||
b <<= 1;
|
||||
WRITE(DOGLCD_SCK, LOW);
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
static inline uint8_t swSpiTransfer_mode_3(uint8_t b) {
|
||||
for (uint8_t i = 0; i < 8; ++i) {
|
||||
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
||||
WRITE(DOGLCD_SCK, LOW);
|
||||
WRITE(DOGLCD_MOSI, state);
|
||||
b <<= 1;
|
||||
WRITE(DOGLCD_SCK, HIGH);
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
static void u8g_sw_spi_shift_out(uint8_t val) {
|
||||
#if U8G_SPI_USE_MODE_3
|
||||
swSpiTransfer_mode_3(val);
|
||||
#else
|
||||
swSpiTransfer_mode_0(val);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void swSpiInit() {
|
||||
#if PIN_EXISTS(LCD_RESET)
|
||||
SET_OUTPUT(LCD_RESET_PIN);
|
||||
#endif
|
||||
SET_OUTPUT(DOGLCD_A0);
|
||||
OUT_WRITE(DOGLCD_SCK, LOW);
|
||||
OUT_WRITE(DOGLCD_MOSI, LOW);
|
||||
OUT_WRITE(DOGLCD_CS, HIGH);
|
||||
}
|
||||
|
||||
uint8_t u8g_com_HAL_MFL_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
switch (msg) {
|
||||
case U8G_COM_MSG_INIT:
|
||||
swSpiInit();
|
||||
break;
|
||||
case U8G_COM_MSG_STOP:
|
||||
break;
|
||||
case U8G_COM_MSG_RESET:
|
||||
#if PIN_EXISTS(LCD_RESET)
|
||||
WRITE(LCD_RESET_PIN, arg_val);
|
||||
#endif
|
||||
break;
|
||||
case U8G_COM_MSG_CHIP_SELECT:
|
||||
#if U8G_SPI_USE_MODE_3 // This LCD SPI is running mode 3 while SD card is running mode 0
|
||||
if (arg_val) { // SCK idle state needs to be set to the proper idle state before
|
||||
// the next chip select goes active
|
||||
WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active
|
||||
WRITE(DOGLCD_CS, LOW);
|
||||
nop; // Hold SCK high for a few ns
|
||||
nop;
|
||||
}
|
||||
else {
|
||||
WRITE(DOGLCD_CS, HIGH);
|
||||
WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive
|
||||
}
|
||||
#else
|
||||
WRITE(DOGLCD_CS, !arg_val);
|
||||
#endif
|
||||
break;
|
||||
case U8G_COM_MSG_WRITE_BYTE:
|
||||
u8g_sw_spi_shift_out(arg_val);
|
||||
break;
|
||||
case U8G_COM_MSG_WRITE_SEQ: {
|
||||
uint8_t* ptr = (uint8_t*)arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
u8g_sw_spi_shift_out(*ptr++);
|
||||
arg_val--;
|
||||
}
|
||||
} break;
|
||||
case U8G_COM_MSG_WRITE_SEQ_P: {
|
||||
uint8_t* ptr = (uint8_t*)arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
u8g_sw_spi_shift_out(u8g_pgm_read(ptr));
|
||||
ptr++;
|
||||
arg_val--;
|
||||
}
|
||||
} break;
|
||||
case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1)
|
||||
WRITE(DOGLCD_A0, arg_val);
|
||||
break;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
93
Marlin/src/HAL/GD32_MFL/eeprom_bl24cxx.cpp
Normal file
93
Marlin/src/HAL/GD32_MFL/eeprom_bl24cxx.cpp
Normal file
|
|
@ -0,0 +1,93 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* PersistentStore for Arduino-style EEPROM interface
|
||||
* with simple implementations supplied by Marlin.
|
||||
*/
|
||||
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(IIC_BL24CXX_EEPROM)
|
||||
|
||||
#include "../shared/eeprom_if.h"
|
||||
#include "../shared/eeprom_api.h"
|
||||
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM."
|
||||
#endif
|
||||
|
||||
size_t PersistentStore::capacity() {
|
||||
return MARLIN_EEPROM_SIZE - eeprom_exclude_size;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
eeprom_init();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
uint16_t written = 0;
|
||||
while (size--) {
|
||||
uint8_t v = *value;
|
||||
uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos);
|
||||
// EPROM has only ~100,000 write cycles,
|
||||
// so only write bytes that have changed!
|
||||
if (v != eeprom_read_byte(p)) {
|
||||
eeprom_write_byte(p, v);
|
||||
if (++written & 0x7F) delay(4); else safe_delay(4);
|
||||
if (eeprom_read_byte(p) != v) {
|
||||
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
crc16(crc, &v, 1);
|
||||
pos++;
|
||||
value++;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
do {
|
||||
const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos));
|
||||
if (writing) *value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
value++;
|
||||
} while (--size);
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // IIC_BL24CXX_EEPROM
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
54
Marlin/src/HAL/GD32_MFL/eeprom_if_iic.cpp
Normal file
54
Marlin/src/HAL/GD32_MFL/eeprom_if_iic.cpp
Normal file
|
|
@ -0,0 +1,54 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Platform-independent Arduino functions for I2C EEPROM.
|
||||
* Enable USE_SHARED_EEPROM if not supplied by the framework.
|
||||
*/
|
||||
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(IIC_BL24CXX_EEPROM)
|
||||
|
||||
#include "../../libs/BL24CXX.h"
|
||||
#include "../shared/eeprom_if.h"
|
||||
|
||||
void eeprom_init() {
|
||||
BL24CXX::init();
|
||||
}
|
||||
|
||||
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::writeOneByte(eeprom_address, value);
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t *pos) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::readOneByte(eeprom_address);
|
||||
}
|
||||
|
||||
#endif // IIC_BL24CXX_EEPROM
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
96
Marlin/src/HAL/GD32_MFL/eeprom_wired.cpp
Normal file
96
Marlin/src/HAL/GD32_MFL/eeprom_wired.cpp
Normal file
|
|
@ -0,0 +1,96 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if USE_WIRED_EEPROM
|
||||
|
||||
/**
|
||||
* PersistentStore for Arduino-style EEPROM interface
|
||||
* with simple implementations supplied by Marlin.
|
||||
*/
|
||||
|
||||
#include "../shared/eeprom_if.h"
|
||||
#include "../shared/eeprom_api.h"
|
||||
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#define MARLIN_EEPROM_SIZE size_t(E2END + 1)
|
||||
#endif
|
||||
|
||||
size_t PersistentStore::capacity() {
|
||||
return MARLIN_EEPROM_SIZE - eeprom_exclude_size;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
eeprom_init();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
uint16_t written = 0;
|
||||
while (size--) {
|
||||
uint8_t v = *value;
|
||||
uint8_t * const p = (uint8_t * const)REAL_EEPROM_ADDR(pos);
|
||||
// EEPROM has only ~100,000 write cycles,
|
||||
// so only write bytes that have changed!
|
||||
if (v != eeprom_read_byte(p)) {
|
||||
eeprom_write_byte(p, v);
|
||||
// Avoid triggering watchdog during long EEPROM writes
|
||||
if (++written & 0x7F)
|
||||
delay(2);
|
||||
else
|
||||
safe_delay(2);
|
||||
if (eeprom_read_byte(p) != v) {
|
||||
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
crc16(crc, &v, 1);
|
||||
pos++;
|
||||
value++;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
do {
|
||||
const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos));
|
||||
if (writing)
|
||||
*value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
value++;
|
||||
} while (--size);
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // USE_WIRED_EEPROM
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
61
Marlin/src/HAL/GD32_MFL/endstop_interrupts.h
Normal file
61
Marlin/src/HAL/GD32_MFL/endstop_interrupts.h
Normal file
|
|
@ -0,0 +1,61 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../module/endstops.h"
|
||||
|
||||
// One ISR for all EXT-Interrupts
|
||||
void endstop_ISR() { endstops.update(); }
|
||||
|
||||
void setup_endstop_interrupts() {
|
||||
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
|
||||
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
|
||||
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
|
||||
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
|
||||
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
|
||||
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
|
||||
TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN));
|
||||
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
|
||||
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
|
||||
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
|
||||
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
|
||||
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
|
||||
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
|
||||
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
|
||||
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
|
||||
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||
TERN_(USE_Z_MIN_PROBE, _ATTACH(Z_MIN_PROBE_PIN));
|
||||
TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN));
|
||||
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
|
||||
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
|
||||
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
|
||||
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
|
||||
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
|
||||
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
|
||||
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
|
||||
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
|
||||
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
|
||||
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
|
||||
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
|
||||
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
|
||||
}
|
||||
97
Marlin/src/HAL/GD32_MFL/fast_pwm.cpp
Normal file
97
Marlin/src/HAL/GD32_MFL/fast_pwm.cpp
Normal file
|
|
@ -0,0 +1,97 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include <PinOpsMap.hpp>
|
||||
#include <PinOps.hpp>
|
||||
#include "timers.h"
|
||||
|
||||
static uint16_t timer_frequency[TIMER_COUNT];
|
||||
|
||||
void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale, const bool invert) {
|
||||
// Calculate duty cycle based on inversion flag
|
||||
const uint16_t duty = invert ? scale - value : value;
|
||||
|
||||
// Check if the pin supports PWM
|
||||
if (PWM_PIN(pin)) {
|
||||
// Get the timer peripheral base associated with the pin
|
||||
const auto timer_base = getPinOpsPeripheralBase<TIMERPinOps, timer::TIMER_Base>(TIMER_PinOps, static_cast<pin_size_t>(pin));
|
||||
|
||||
// Initialize the timer instance
|
||||
auto& TimerInstance = GeneralTimer::get_instance(timer_base);
|
||||
|
||||
// Get channel and previous channel mode
|
||||
const auto channel = getPackedPinChannel(getPackedPinOps(TIMER_PinOps, static_cast<pin_size_t>(pin)));
|
||||
const InputOutputMode previous = TimerInstance.getChannelMode(channel);
|
||||
|
||||
if (timer_frequency[static_cast<size_t>(timer_base)] == 0) {
|
||||
set_pwm_frequency(pin, PWM_FREQUENCY);
|
||||
}
|
||||
|
||||
// Set the PWM duty cycle
|
||||
TimerInstance.setCaptureCompare(channel, duty, CCFormat::B8);
|
||||
|
||||
// Configure pin as PWM output
|
||||
pinOpsPinout(TIMER_PinOps, static_cast<pin_size_t>(pin));
|
||||
|
||||
// Set channel mode if not already set and start timer
|
||||
if (previous != InputOutputMode::PWM0) {
|
||||
TimerInstance.setChannelMode(channel, InputOutputMode::PWM0, static_cast<pin_size_t>(pin));
|
||||
TimerInstance.start();
|
||||
}
|
||||
} else {
|
||||
pinMode(pin, OUTPUT);
|
||||
digitalWrite(pin, duty < scale / 2 ? LOW : HIGH);
|
||||
}
|
||||
}
|
||||
|
||||
void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
|
||||
// Check if the pin supports PWM
|
||||
if (!PWM_PIN(pin)) return;
|
||||
|
||||
// Get the timer peripheral base associated with the pin
|
||||
const auto timer_base = getPinOpsPeripheralBase<TIMERPinOps, timer::TIMER_Base>(TIMER_PinOps, static_cast<pin_size_t>(pin));
|
||||
|
||||
// Guard against modifying protected timers
|
||||
#ifdef STEP_TIMER
|
||||
if (timer_base == static_cast<timer::TIMER_Base>(STEP_TIMER)) return;
|
||||
#endif
|
||||
#ifdef TEMP_TIMER
|
||||
if (timer_base == static_cast<timer::TIMER_Base>(TEMP_TIMER)) return;
|
||||
#endif
|
||||
#if defined(PULSE_TIMER) && MF_TIMER_PULSE != MF_TIMER_STEP
|
||||
if (timer_base == static_cast<timer::TIMER_Base>(PULSE_TIMER)) return;
|
||||
#endif
|
||||
|
||||
// Initialize the timer instance
|
||||
auto& TimerInstance = GeneralTimer::get_instance(timer_base);
|
||||
|
||||
TimerInstance.setRolloverValue(f_desired, TimerFormat::HERTZ);
|
||||
timer_frequency[timer_base_to_index(timer_base)] = f_desired;
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
82
Marlin/src/HAL/GD32_MFL/fastio.h
Normal file
82
Marlin/src/HAL/GD32_MFL/fastio.h
Normal file
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// Fast I/O interfaces for GD32F303RE
|
||||
|
||||
#include <GPIO.hpp>
|
||||
#include <PinOps.hpp>
|
||||
#include <PinOpsMap.hpp>
|
||||
|
||||
static inline void fast_write_pin_wrapper(pin_size_t IO, bool V) {
|
||||
if (V) gpio::fast_set_pin(getPortFromPin(IO), getPinInPort(IO));
|
||||
else gpio::fast_clear_pin(getPortFromPin(IO), getPinInPort(IO));
|
||||
}
|
||||
|
||||
static inline bool fast_read_pin_wrapper(pin_size_t IO) {
|
||||
return gpio::fast_read_pin(getPortFromPin(IO), getPinInPort(IO));
|
||||
}
|
||||
|
||||
static inline void fast_toggle_pin_wrapper(pin_size_t IO) {
|
||||
gpio::fast_toggle_pin(getPortFromPin(IO), getPinInPort(IO));
|
||||
}
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
#ifndef PWM
|
||||
#define PWM OUTPUT
|
||||
#endif
|
||||
|
||||
#define _WRITE(IO, V) fast_write_pin_wrapper(IO, V)
|
||||
#define _READ(IO) fast_read_pin_wrapper(IO)
|
||||
#define _TOGGLE(IO) fast_toggle_pin_wrapper(IO)
|
||||
|
||||
#define _GET_MODE(IO)
|
||||
#define _SET_MODE(IO, M) pinMode((IO), (M))
|
||||
#define _SET_OUTPUT(IO) pinMode((IO), OUTPUT)
|
||||
#define _SET_OUTPUT_OD(IO) pinMode((IO), OUTPUT_OPEN_DRAIN)
|
||||
|
||||
#define WRITE(IO, V) _WRITE((IO), (V))
|
||||
#define READ(IO) _READ(IO)
|
||||
#define TOGGLE(IO) _TOGGLE(IO)
|
||||
|
||||
#define OUT_WRITE(IO, V) do { _SET_OUTPUT(IO); WRITE((IO), (V)); } while (0)
|
||||
#define OUT_WRITE_OD(IO, V) do { _SET_OUTPUT_OD(IO); WRITE((IO), (V)); } while (0)
|
||||
|
||||
#define SET_INPUT(IO) _SET_MODE((IO), INPUT)
|
||||
#define SET_INPUT_PULLUP(IO) _SET_MODE((IO), INPUT_PULLUP)
|
||||
#define SET_INPUT_PULLDOWN(IO) _SET_MODE((IO), INPUT_PULLDOWN)
|
||||
#define SET_OUTPUT(IO) OUT_WRITE((IO), LOW)
|
||||
#define SET_OUTPUT_OD(IO) OUT_WRITE_OD((IO), LOW)
|
||||
#define SET_PWM(IO) _SET_MODE((IO), PWM)
|
||||
|
||||
#define IS_INPUT(IO)
|
||||
#define IS_OUTPUT(IO)
|
||||
|
||||
#define PWM_PIN(P) isPinInPinOps(TIMER_PinOps, P)
|
||||
#define NO_COMPILE_TIME_PWM
|
||||
|
||||
// Wrappers for digitalRead and digitalWrite
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO, V) digitalWrite((IO), (V))
|
||||
26
Marlin/src/HAL/GD32_MFL/inc/Conditionals_LCD.h
Normal file
26
Marlin/src/HAL/GD32_MFL/inc/Conditionals_LCD.h
Normal file
|
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
|
||||
#define U8G_SW_SPI_MFL 1
|
||||
#endif
|
||||
26
Marlin/src/HAL/GD32_MFL/inc/Conditionals_adv.h
Normal file
26
Marlin/src/HAL/GD32_MFL/inc/Conditionals_adv.h
Normal file
|
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#if ALL(HAS_MEDIA, USBD_USE_CDC_MSC)
|
||||
#define HAS_SD_HOST_DRIVE 1
|
||||
#endif
|
||||
29
Marlin/src/HAL/GD32_MFL/inc/Conditionals_post.h
Normal file
29
Marlin/src/HAL/GD32_MFL/inc/Conditionals_post.h
Normal file
|
|
@ -0,0 +1,29 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// If no real or emulated EEPROM selected, fall back to SD emulation
|
||||
#if USE_FALLBACK_EEPROM
|
||||
#define SDCARD_EEPROM_EMULATION
|
||||
#elif ANY(I2C_EEPROM, SPI_EEPROM)
|
||||
#define USE_SHARED_EEPROM 1
|
||||
#endif
|
||||
22
Marlin/src/HAL/GD32_MFL/inc/Conditionals_type.h
Normal file
22
Marlin/src/HAL/GD32_MFL/inc/Conditionals_type.h
Normal file
|
|
@ -0,0 +1,22 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
97
Marlin/src/HAL/GD32_MFL/inc/SanityCheck.h
Normal file
97
Marlin/src/HAL/GD32_MFL/inc/SanityCheck.h
Normal file
|
|
@ -0,0 +1,97 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// Test MFL GD32 specific configuration values for errors at compile-time.
|
||||
#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA
|
||||
#undef SDCARD_EEPROM_EMULATION // avoid additional error noise
|
||||
#if USE_FALLBACK_EEPROM
|
||||
#warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
|
||||
#endif
|
||||
#error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
|
||||
#endif
|
||||
|
||||
#if ENABLED(FLASH_EEPROM_LEVELING)
|
||||
#error "FLASH_EEPROM_LEVELING is not supported on GD32."
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
#error "SERIAL_STATS_MAX_RX_QUEUED is not supported on GD32."
|
||||
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
#error "SERIAL_STATS_DROPPED_RX is not supported on GD32."
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_SOC && defined(ATEMP) && TEMP_SOC_PIN != ATEMP
|
||||
#error "TEMP_SENSOR_SOC requires 'TEMP_SOC_PIN ATEMP' on GD32"
|
||||
#endif
|
||||
|
||||
// Check for common serial pin conflicts
|
||||
#define _CHECK_SERIAL_PIN(N) (( \
|
||||
BTN_EN1 == N || BTN_EN2 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \
|
||||
SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N || \
|
||||
Y_STEP_PIN == N || Y_ENABLE_PIN == N || E0_ENABLE_PIN == N || POWER_LOSS_PIN == N \
|
||||
))
|
||||
|
||||
#define CHECK_SERIAL_PIN(T, N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN)
|
||||
|
||||
#if SERIAL_IN_USE(0)
|
||||
#if CHECK_SERIAL_PIN(TX, 0)
|
||||
#error "Serial Port 0 TX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#if CHECK_SERIAL_PIN(RX, 0)
|
||||
#error "Serial Port 0 RX IO pins conflict with another pin on the board."
|
||||
#endif
|
||||
#endif
|
||||
#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
|
||||
#undef CHECK_SERIAL_PIN
|
||||
#undef _CHECK_SERIAL_PIN
|
||||
102
Marlin/src/HAL/GD32_MFL/pinsDebug.h
Normal file
102
Marlin/src/HAL/GD32_MFL/pinsDebug.h
Normal file
|
|
@ -0,0 +1,102 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Pins Debugging for GD32
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include <Arduino.h>
|
||||
#include <PinOps.hpp>
|
||||
#include <Analog.h>
|
||||
|
||||
#ifndef TOTAL_PIN_COUNT
|
||||
#error "Expected TOTAL_PIN_COUNT not found."
|
||||
#endif
|
||||
|
||||
#define NUM_DIGITAL_PINS TOTAL_PIN_COUNT
|
||||
#define NUMBER_PINS_TOTAL TOTAL_PIN_COUNT
|
||||
|
||||
#define getPinByIndex(x) pin_t(pin_array[x].pin)
|
||||
#define isValidPin(P) WITHIN(P, 0, (NUM_DIGITAL_PINS - 1))
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define printPinNumber(P) do { sprintf_P(buffer, PSTR("%3hd "), pin_t(P)); SERIAL_ECHO(buffer); } while (0)
|
||||
#define printPinAnalog(P) do { sprintf_P(buffer, PSTR(" (A%2d) "), pin_t(getAdcChannelFromPin(P))); SERIAL_ECHO(buffer); } while (0)
|
||||
#define printPinNameByIndex(x) do { sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); } while (0)
|
||||
|
||||
#define MULTI_NAME_PAD 21 // Space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
#ifndef M43_NEVER_TOUCH
|
||||
#define M43_NEVER_TOUCH(x) WITHIN(x, 9, 10) // SERIAL pins: PA9(TX) PA10(RX)
|
||||
#endif
|
||||
|
||||
bool isAnalogPin(const pin_t pin) {
|
||||
if (!isValidPin(pin)) return false;
|
||||
|
||||
if (getAdcChannel(pin) != adc::ADC_Channel::INVALID) {
|
||||
auto& instance = gpio::GPIO::get_instance(getPortFromPin(pin)).value();
|
||||
return instance.get_pin_mode(getPinInPort(pin)) == gpio::Pin_Mode::ANALOG && !M43_NEVER_TOUCH(pin);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool getValidPinMode(const pin_t pin) {
|
||||
if (!isValidPin(pin)) return false;
|
||||
|
||||
auto& instance = gpio::GPIO::get_instance(getPortFromPin(pin)).value();
|
||||
gpio::Pin_Mode mode = instance.get_pin_mode(getPinInPort(pin));
|
||||
|
||||
return mode != gpio::Pin_Mode::ANALOG && mode != gpio::Pin_Mode::INPUT_FLOATING &&
|
||||
mode != gpio::Pin_Mode::INPUT_PULLUP && mode != gpio::Pin_Mode::INPUT_PULLDOWN;
|
||||
}
|
||||
|
||||
bool getPinIsDigitalByIndex(const int16_t index) {
|
||||
const pin_t pin = getPinByIndex(index);
|
||||
return (!isAnalogPin(pin));
|
||||
}
|
||||
|
||||
int8_t digitalPinToAnalogIndex(const pin_t pin) {
|
||||
if (!isValidPin(pin) || !isAnalogPin(pin)) return -1;
|
||||
return pin; // Analog and digital pin indexes are shared
|
||||
}
|
||||
|
||||
bool pwm_status(const pin_t pin) { return false; }
|
||||
void printPinPWM(const pin_t pin) { /* TODO */ }
|
||||
void printPinPort(const pin_t pin) { /* TODO */ }
|
||||
233
Marlin/src/HAL/GD32_MFL/sdio.cpp
Normal file
233
Marlin/src/HAL/GD32_MFL/sdio.cpp
Normal file
|
|
@ -0,0 +1,233 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(ONBOARD_SDIO)
|
||||
|
||||
#include <PinOpsMap.hpp>
|
||||
#include <PinOps.hpp>
|
||||
#include "SDCard.h"
|
||||
#include "sdio.h"
|
||||
|
||||
using namespace sdio;
|
||||
|
||||
#define TARGET_CLOCK 6000000U
|
||||
#define BLOCK_SIZE 512U
|
||||
#define CARD_TIMEOUT 500 // ms
|
||||
#define READ_RETRIES 3U
|
||||
|
||||
inline constexpr uint32_t TARGET_SDIO_CLOCK = TARGET_CLOCK;
|
||||
inline constexpr uint32_t SDIO_BLOCK_SIZE = BLOCK_SIZE;
|
||||
inline constexpr uint32_t SD_TIMEOUT = CARD_TIMEOUT;
|
||||
inline constexpr uint8_t SDIO_READ_RETRIES = READ_RETRIES;
|
||||
|
||||
Card_State cardState = Card_State::READY;
|
||||
|
||||
bool SDIO_SetBusWidth(Bus_Width width) {
|
||||
return (CardDMA_I.set_hardware_bus_width(width) == SDIO_Error_Type::OK);
|
||||
}
|
||||
|
||||
void mfl_sdio_init() {
|
||||
pinOpsPinout(SD_CMD_PinOps, static_cast<pin_size_t>(SDIO_CMD_PIN));
|
||||
pinOpsPinout(SD_CK_PinOps, static_cast<pin_size_t>(SDIO_CK_PIN));
|
||||
pinOpsPinout(SD_DATA0_PinOps, static_cast<pin_size_t>(SDIO_D0_PIN));
|
||||
pinOpsPinout(SD_DATA1_PinOps, static_cast<pin_size_t>(SDIO_D1_PIN));
|
||||
pinOpsPinout(SD_DATA2_PinOps, static_cast<pin_size_t>(SDIO_D2_PIN));
|
||||
pinOpsPinout(SD_DATA3_PinOps, static_cast<pin_size_t>(SDIO_D3_PIN));
|
||||
|
||||
NVIC_EnableIRQ(DMA1_Channel3_4_IRQn);
|
||||
NVIC_EnableIRQ(SDIO_IRQn);
|
||||
}
|
||||
|
||||
bool SDIO_Init() {
|
||||
SDIO_Error_Type result = SDIO_Error_Type::OK;
|
||||
uint8_t retryCount = SDIO_READ_RETRIES;
|
||||
|
||||
mfl_sdio_init();
|
||||
|
||||
uint8_t retries = retryCount;
|
||||
for (;;) {
|
||||
hal.watchdog_refresh();
|
||||
result = CardDMA_I.init();
|
||||
if (result == SDIO_Error_Type::OK) break;
|
||||
if (!--retries) return false;
|
||||
}
|
||||
|
||||
CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, false, false);
|
||||
|
||||
retries = retryCount;
|
||||
for (;;) {
|
||||
hal.watchdog_refresh();
|
||||
if (SDIO_SetBusWidth(Bus_Width::WIDTH_4BIT)) break;
|
||||
if (!--retries) break;
|
||||
}
|
||||
|
||||
CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, true, true);
|
||||
|
||||
// Fallback
|
||||
if (!retries) {
|
||||
mfl_sdio_init();
|
||||
retries = retryCount;
|
||||
for (;;) {
|
||||
hal.watchdog_refresh();
|
||||
result = CardDMA_I.init();
|
||||
if (result == SDIO_Error_Type::OK) break;
|
||||
if (!--retries) return false;
|
||||
}
|
||||
CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, false, true);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t* src, uint8_t* dst) {
|
||||
hal.watchdog_refresh();
|
||||
SDIO_Error_Type result = SDIO_Error_Type::OK;
|
||||
|
||||
// Write
|
||||
if (src) {
|
||||
result = CardDMA_I.write(reinterpret_cast<uint8_t*>(const_cast<uint8_t*>(src)), block, 1);
|
||||
}
|
||||
// Read
|
||||
else {
|
||||
result = CardDMA_I.read(dst, block, 1);
|
||||
}
|
||||
|
||||
if (result != SDIO_Error_Type::OK) {
|
||||
return false;
|
||||
}
|
||||
|
||||
millis_t timeout = millis() + SD_TIMEOUT;
|
||||
while (CardDMA_I.get_state() != sdio::Operational_State::READY) {
|
||||
if (ELAPSED(millis(), timeout)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
CardDMA_I.check_dma_complete();
|
||||
|
||||
timeout = millis() + SD_TIMEOUT;
|
||||
do {
|
||||
result = CardDMA_I.get_card_state(&cardState);
|
||||
if (ELAPSED(millis(), timeout)) {
|
||||
return false;
|
||||
}
|
||||
} while (result == SDIO_Error_Type::OK && cardState != sdio::Card_State::TRANSFER);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool SDIO_ReadBlock(uint32_t block, uint8_t* dst) {
|
||||
// Check if the address is aligned to 4 bytes
|
||||
if (reinterpret_cast<uint32_t>(dst) & 0x03) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t retries = SDIO_READ_RETRIES;
|
||||
while (retries--) {
|
||||
if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool SDIO_WriteBlock(uint32_t block, const uint8_t* src) {
|
||||
// Check if the address is aligned to 4 bytes
|
||||
if (reinterpret_cast<uint32_t>(src) & 0x03) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t retries = SDIO_READ_RETRIES;
|
||||
while (retries--) {
|
||||
if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) {
|
||||
return true;
|
||||
delay(10);
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool SDIO_IsReady() {
|
||||
return (CardDMA_I.get_state() == sdio::Operational_State::READY);
|
||||
}
|
||||
|
||||
uint32_t SDIO_GetCardSize() {
|
||||
return CardDMA_I.get_card_capacity();
|
||||
}
|
||||
|
||||
// DMA interrupt handler
|
||||
void DMA1_IRQHandler() {
|
||||
auto& dma_instance = CardDMA_I.get_dma_instance();
|
||||
bool is_receive = CardDMA_I.get_is_sdio_rx();
|
||||
|
||||
// Check for Transfer Complete Interrupt
|
||||
if (dma_instance.get_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_FTFIF)) {
|
||||
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, false);
|
||||
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, false);
|
||||
dma_instance.clear_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_FTFIF);
|
||||
if (is_receive) {
|
||||
CardDMA_I.set_sdio_dma_enable(false);
|
||||
CardDMA_I.clear_sdio_data_flags();
|
||||
CardDMA_I.set_state(sdio::Operational_State::READY);
|
||||
} else {
|
||||
CardDMA_I.set_data_end_interrupt();
|
||||
}
|
||||
// Signal that transfer is complete
|
||||
CardDMA_I.set_transfer_end(true);
|
||||
}
|
||||
|
||||
else if (dma_instance.get_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_ERRIF)) {
|
||||
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_HTFIE, false);
|
||||
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, false);
|
||||
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, false);
|
||||
// Clear all flags
|
||||
dma_instance.clear_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_GIF);
|
||||
// Signal that an error occurred
|
||||
CardDMA_I.set_transfer_error(SDIO_Error_Type::ERROR);
|
||||
CardDMA_I.set_state(sdio::Operational_State::READY);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
extern "C" {
|
||||
|
||||
void SDIO_IRQHandler(void) {
|
||||
CardDMA_I.handle_interrupts();
|
||||
}
|
||||
|
||||
void DMA1_Channel3_4_IRQHandler(void) {
|
||||
DMA1_IRQHandler();
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
|
||||
|
||||
#endif // ONBOARD_SDIO
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
36
Marlin/src/HAL/GD32_MFL/sdio.h
Normal file
36
Marlin/src/HAL/GD32_MFL/sdio.h
Normal file
|
|
@ -0,0 +1,36 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <SDIO.hpp>
|
||||
#include <DMA.hpp>
|
||||
|
||||
#define SDIO_D0_PIN PC8
|
||||
#define SDIO_D1_PIN PC9
|
||||
#define SDIO_D2_PIN PC10
|
||||
#define SDIO_D3_PIN PC11
|
||||
#define SDIO_CK_PIN PC12
|
||||
#define SDIO_CMD_PIN PD2
|
||||
|
||||
void sdio_mfl_init();
|
||||
bool SDIO_SetBusWidth(sdio::Bus_Width width);
|
||||
void DMA1_IRQHandler(dma::DMA_Channel channel);
|
||||
32
Marlin/src/HAL/GD32_MFL/spi_pins.h
Normal file
32
Marlin/src/HAL/GD32_MFL/spi_pins.h
Normal file
|
|
@ -0,0 +1,32 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// Define SPI Pins: SCK, MISO, MOSI
|
||||
#ifndef SD_SCK_PIN
|
||||
#define SD_SCK_PIN PIN_SPI_SCK
|
||||
#endif
|
||||
#ifndef SD_MISO_PIN
|
||||
#define SD_MISO_PIN PIN_SPI_MISO
|
||||
#endif
|
||||
#ifndef SD_MOSI_PIN
|
||||
#define SD_MOSI_PIN PIN_SPI_MOSI
|
||||
#endif
|
||||
29
Marlin/src/HAL/GD32_MFL/temp_soc.h
Normal file
29
Marlin/src/HAL/GD32_MFL/temp_soc.h
Normal file
|
|
@ -0,0 +1,29 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#define TS_TYPICAL_V 1.405
|
||||
#define TS_TYPICAL_TEMP 25
|
||||
#define TS_TYPICAL_SLOPE 4.5
|
||||
|
||||
// TODO: Implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable)
|
||||
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000)) / ((TS_TYPICAL_SLOPE) / 1000) + TS_TYPICAL_TEMP)
|
||||
233
Marlin/src/HAL/GD32_MFL/timers.cpp
Normal file
233
Marlin/src/HAL/GD32_MFL/timers.cpp
Normal file
|
|
@ -0,0 +1,233 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "../platforms.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_MFL
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "timers.h"
|
||||
|
||||
// ------------------------
|
||||
// Local defines
|
||||
// ------------------------
|
||||
|
||||
#define SWSERIAL_TIMER_IRQ_PRIORITY_DEFAULT 1 // Requires tight bit timing to communicate reliably with TMC drivers
|
||||
#define SERVO_TIMER_IRQ_PRIORITY_DEFAULT 1 // Requires tight PWM timing to control a BLTouch reliably
|
||||
#define STEP_TIMER_IRQ_PRIORITY_DEFAULT 2
|
||||
#define TEMP_TIMER_IRQ_PRIORITY_DEFAULT 14 // Low priority avoids interference with other hardware and timers
|
||||
|
||||
#ifndef TIMER_IRQ_PRIORITY
|
||||
#define TIMER_IRQ_PRIORITY 12
|
||||
#endif
|
||||
|
||||
#ifndef STEP_TIMER_IRQ_PRIORITY
|
||||
#define STEP_TIMER_IRQ_PRIORITY STEP_TIMER_IRQ_PRIORITY_DEFAULT
|
||||
#endif
|
||||
|
||||
#ifndef TEMP_TIMER_IRQ_PRIORITY
|
||||
#define TEMP_TIMER_IRQ_PRIORITY TEMP_TIMER_IRQ_PRIORITY_DEFAULT
|
||||
#endif
|
||||
|
||||
#if HAS_TMC_SW_SERIAL
|
||||
#include <SoftwareSerial.h>
|
||||
#ifndef SWSERIAL_TIMER_IRQ_PRIORITY
|
||||
#define SWSERIAL_TIMER_IRQ_PRIORITY SWSERIAL_TIMER_IRQ_PRIORITY_DEFAULT
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_SERVOS
|
||||
#include "Servo.h"
|
||||
#ifndef SERVO_TIMER_IRQ_PRIORITY
|
||||
#define SERVO_TIMER_IRQ_PRIORITY SERVO_TIMER_IRQ_PRIORITY_DEFAULT
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(SPEAKER)
|
||||
// The MFL framework default timer priority is 12. The TEMP timer must have lower priority
|
||||
// than this due to the long running temperature ISR, and STEP timer should higher priority.
|
||||
#if !(TIMER_IRQ_PRIORITY > STEP_TIMER_IRQ_PRIORITY && TIMER_IRQ_PRIORITY < TEMP_TIMER_IRQ_PRIORITY)
|
||||
#error "Default timer interrupt priority is unspecified or set to a value which may degrade performance."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef HAL_TIMER_RATE
|
||||
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
|
||||
#endif
|
||||
|
||||
#ifndef STEP_TIMER
|
||||
#define STEP_TIMER MF_TIMER_STEP
|
||||
#endif
|
||||
#ifndef TEMP_TIMER
|
||||
#define TEMP_TIMER MF_TIMER_TEMP
|
||||
#endif
|
||||
|
||||
GeneralTimer& Step_Timer = GeneralTimer::get_instance(static_cast<timer::TIMER_Base>(STEP_TIMER));
|
||||
GeneralTimer& Temp_Timer = GeneralTimer::get_instance(static_cast<timer::TIMER_Base>(TEMP_TIMER));
|
||||
|
||||
bool is_step_timer_initialized = false;
|
||||
bool is_temp_timer_initialized = false;
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
// Retrieves the clock frequency of the stepper timer
|
||||
uint32_t GetStepperTimerClkFreq() {
|
||||
return Step_Timer.getTimerClockFrequency();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Starts a hardware timer
|
||||
*
|
||||
* If the timer is not already initialized, this function will initialize it with the given frequency.
|
||||
* The timer is started immediately after initialization
|
||||
*
|
||||
* @param timer The timer base index to start
|
||||
* @param frequency The frequency at which the timer should run
|
||||
* @return None
|
||||
*/
|
||||
void HAL_timer_start(const uint8_t timer_number, const uint32_t frequency) {
|
||||
if (HAL_timer_initialized(timer_number) || (timer_number != MF_TIMER_STEP && timer_number != MF_TIMER_TEMP))
|
||||
return;
|
||||
|
||||
const bool is_step = (timer_number == MF_TIMER_STEP);
|
||||
const uint8_t priority = is_step ?
|
||||
static_cast<uint8_t>(STEP_TIMER_IRQ_PRIORITY) :
|
||||
static_cast<uint8_t>(TEMP_TIMER_IRQ_PRIORITY);
|
||||
|
||||
// Get the reference of the timer instance
|
||||
GeneralTimer& timer = is_step ? Step_Timer : Temp_Timer;
|
||||
|
||||
if (is_step) {
|
||||
timer.setPrescaler(STEPPER_TIMER_PRESCALE);
|
||||
timer.setRolloverValue(_MIN(static_cast<hal_timer_t>(HAL_TIMER_TYPE_MAX),
|
||||
(HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)),
|
||||
TimerFormat::TICK);
|
||||
is_step_timer_initialized = true;
|
||||
}
|
||||
else {
|
||||
timer.setRolloverValue(frequency, TimerFormat::HERTZ);
|
||||
is_temp_timer_initialized = true;
|
||||
}
|
||||
|
||||
timer.setAutoReloadEnable(false);
|
||||
timer.setInterruptPriority(priority, 0U);
|
||||
HAL_timer_enable_interrupt(timer_number);
|
||||
timer.start();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables the interrupt for the specified timer
|
||||
*
|
||||
* @param handle The timer handle for which to enable the interrupt
|
||||
* @return None
|
||||
*/
|
||||
void HAL_timer_enable_interrupt(const uint8_t timer_number) {
|
||||
if (!HAL_timer_initialized(timer_number)) return;
|
||||
|
||||
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
|
||||
|
||||
if (timer_number == MF_TIMER_STEP && !timer.hasInterrupt())
|
||||
timer.attachInterrupt(Step_Handler);
|
||||
else if (timer_number == MF_TIMER_TEMP && !timer.hasInterrupt())
|
||||
timer.attachInterrupt(Temp_Handler);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Disables the interrupt for the specified timer
|
||||
*
|
||||
* @param handle The timer handle for which to disable the interrupt
|
||||
* @return None
|
||||
*/
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_number) {
|
||||
if (!HAL_timer_initialized(timer_number)) return;
|
||||
|
||||
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
|
||||
if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP)
|
||||
timer.detachInterrupt();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks if the interrupt is enabled for the specified timer
|
||||
*
|
||||
* @param handle The timer handle to check
|
||||
* @return True if the interrupt is enabled, false otherwise
|
||||
*/
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_number) {
|
||||
if (!HAL_timer_initialized(timer_number)) return false;
|
||||
|
||||
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
|
||||
return (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP)
|
||||
? timer.hasInterrupt()
|
||||
: false;
|
||||
}
|
||||
|
||||
// Sets the interrupt priorities for timers used by TMC SW serial and servos.
|
||||
void SetTimerInterruptPriorities() {
|
||||
TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIORITY, 0));
|
||||
TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIORITY, 0));
|
||||
}
|
||||
|
||||
// ------------------------
|
||||
// Detect timer conflicts
|
||||
// ------------------------
|
||||
|
||||
TERN_(SPEAKER, static constexpr timer::TIMER_Base timer_tone[] = {static_cast<timer::TIMER_Base>(TIMER_TONE)});
|
||||
TERN_(HAS_SERVOS, static constexpr timer::TIMER_Base timer_servo[] = {static_cast<timer::TIMER_Base>(TIMER_SERVO)});
|
||||
|
||||
enum TimerPurpose {
|
||||
PURPOSE_TONE,
|
||||
PURPOSE_SERVO,
|
||||
PURPOSE_STEP,
|
||||
PURPOSE_TEMP
|
||||
};
|
||||
|
||||
// List of timers to check for conflicts
|
||||
// Includes the timer purpose to ease debugging when evaluating at build-time
|
||||
// This cannot yet account for timers used for PWM output, such as for fans
|
||||
static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = {
|
||||
#if ENABLED(SPEAKER)
|
||||
{ PURPOSE_TONE, timer_base_to_index(timer_tone[0]) }, // Set in variant.h
|
||||
#endif
|
||||
#if HAS_SERVOS
|
||||
{ PURPOSE_SERVO, timer_base_to_index(timer_servo[0]) }, // Set in variant.h
|
||||
#endif
|
||||
{ PURPOSE_STEP, MF_TIMER_STEP },
|
||||
{ PURPOSE_TEMP, MF_TIMER_TEMP },
|
||||
};
|
||||
|
||||
// Verifies if there are any timer conflicts in the timers_in_use array
|
||||
static constexpr bool verify_no_timer_conflicts() {
|
||||
for (uint8_t i = 0; i < COUNT(timers_in_use); i++)
|
||||
for (uint8_t j = i + 1; j < COUNT(timers_in_use); j++)
|
||||
if (timers_in_use[i].t == timers_in_use[j].t)
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// If this assertion fails at compile time, review the timers_in_use array.
|
||||
// If default_envs is defined properly in platformio.ini, VSCode can evaluate the array
|
||||
// when hovering over it, making it easy to identify the conflicting timers
|
||||
static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict.");
|
||||
|
||||
#endif // ARDUINO_ARCH_MFL
|
||||
145
Marlin/src/HAL/GD32_MFL/timers.h
Normal file
145
Marlin/src/HAL/GD32_MFL/timers.h
Normal file
|
|
@ -0,0 +1,145 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include <GeneralTimer.h>
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
// Timer configuration constants
|
||||
#define STEPPER_TIMER_RATE 2000000
|
||||
#define TEMP_TIMER_FREQUENCY 1000
|
||||
|
||||
// Timer instance definitions
|
||||
#define MF_TIMER_STEP 3
|
||||
#define MF_TIMER_TEMP 1
|
||||
#define MF_TIMER_PULSE MF_TIMER_STEP
|
||||
|
||||
#define hal_timer_t uint32_t
|
||||
#define HAL_TIMER_TYPE_MAX UINT16_MAX
|
||||
|
||||
extern uint32_t GetStepperTimerClkFreq();
|
||||
|
||||
// Timer prescaler calculations
|
||||
#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper timer ticks per µs
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
|
||||
// Timer interrupt priorities
|
||||
#define STEP_TIMER_IRQ_PRIORITY 2
|
||||
#define TEMP_TIMER_IRQ_PRIORITY 14
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
extern void Step_Handler();
|
||||
extern void Temp_Handler();
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
#define HAL_STEP_TIMER_ISR() void Step_Handler()
|
||||
#endif
|
||||
#ifndef HAL_TEMP_TIMER_ISR
|
||||
#define HAL_TEMP_TIMER_ISR() void Temp_Handler()
|
||||
#endif
|
||||
|
||||
extern GeneralTimer& Step_Timer;
|
||||
extern GeneralTimer& Temp_Timer;
|
||||
|
||||
extern bool is_step_timer_initialized;
|
||||
extern bool is_temp_timer_initialized;
|
||||
|
||||
// Build-time mapping between timer base and index. Used in timers.cpp and fast_pwm.cpp
|
||||
static inline constexpr struct {timer::TIMER_Base base; uint8_t timer_number;} base_to_index[] = {
|
||||
{ timer::TIMER_Base::TIMER0_BASE, 0 },
|
||||
{ timer::TIMER_Base::TIMER1_BASE, 1 },
|
||||
{ timer::TIMER_Base::TIMER2_BASE, 2 },
|
||||
{ timer::TIMER_Base::TIMER3_BASE, 3 },
|
||||
{ timer::TIMER_Base::TIMER4_BASE, 4 },
|
||||
{ timer::TIMER_Base::TIMER5_BASE, 5 },
|
||||
{ timer::TIMER_Base::TIMER6_BASE, 6 },
|
||||
{ timer::TIMER_Base::TIMER7_BASE, 7 }
|
||||
};
|
||||
|
||||
// Converts a timer base to an integer timer index.
|
||||
constexpr int timer_base_to_index(timer::TIMER_Base base) {
|
||||
for (const auto& timer : base_to_index) {
|
||||
if (timer.base == base) {
|
||||
return static_cast<int>(timer.timer_number);
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
void HAL_timer_start(const uint8_t timer, const uint32_t frequency);
|
||||
void HAL_timer_enable_interrupt(const uint8_t timer);
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer);
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer);
|
||||
|
||||
// Configure timer priorities for peripherals such as Software Serial or Servos.
|
||||
// Exposed here to allow all timer priority information to reside in timers.cpp
|
||||
void SetTimerInterruptPriorities();
|
||||
|
||||
// FORCE_INLINE because these are used in performance-critical situations
|
||||
FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_number) {
|
||||
return (timer_number == MF_TIMER_STEP) ? is_step_timer_initialized :
|
||||
(timer_number == MF_TIMER_TEMP) ? is_temp_timer_initialized :
|
||||
false;
|
||||
}
|
||||
|
||||
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_number) {
|
||||
if (!HAL_timer_initialized(timer_number)) return 0U;
|
||||
|
||||
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
|
||||
|
||||
return (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP)
|
||||
? timer.getCounter(TimerFormat::TICK)
|
||||
: 0U;
|
||||
}
|
||||
|
||||
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_number, const hal_timer_t value) {
|
||||
if (!HAL_timer_initialized(timer_number)) return;
|
||||
|
||||
const uint32_t new_value = static_cast<uint32_t>(value + 1U);
|
||||
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
|
||||
|
||||
if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) {
|
||||
timer.setRolloverValue(new_value, TimerFormat::TICK);
|
||||
if (value < static_cast<hal_timer_t>(timer.getCounter(TimerFormat::TICK)))
|
||||
timer.refresh();
|
||||
}
|
||||
}
|
||||
|
||||
#define HAL_timer_isr_prologue(T) NOOP
|
||||
#define HAL_timer_isr_epilogue(T) NOOP
|
||||
26
Marlin/src/HAL/GD32_MFL/u8g/LCD_defines.h
Normal file
26
Marlin/src/HAL/GD32_MFL/u8g/LCD_defines.h
Normal file
|
|
@ -0,0 +1,26 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// MFL LCD-specific defines
|
||||
uint8_t u8g_com_HAL_MFL_sw_spi_fn(u8g_t* u8g, uint8_t msg, uint8_t arg_val, void* arg_ptr); // u8g_com_mfl_swspi.cpp
|
||||
#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_MFL_sw_spi_fn
|
||||
|
|
@ -2,6 +2,9 @@
|
|||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
|
|
|
|||
|
|
@ -2,6 +2,9 @@
|
|||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
|
|
|
|||
|
|
@ -2,6 +2,9 @@
|
|||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
|
|
|
|||
|
|
@ -37,6 +37,8 @@
|
|||
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LPC1768/NAME)
|
||||
#elif defined(ARDUINO_ARCH_HC32)
|
||||
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/HC32/NAME)
|
||||
#elif defined(ARDUINO_ARCH_MFL)
|
||||
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/GD32_MFL/NAME)
|
||||
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
|
||||
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32F1/NAME)
|
||||
#elif defined(ARDUINO_ARCH_STM32)
|
||||
|
|
|
|||
|
|
@ -76,6 +76,8 @@
|
|||
#include "../LPC1768/Servo.h"
|
||||
#elif defined(ARDUINO_ARCH_HC32)
|
||||
#include "../HC32/Servo.h"
|
||||
#elif defined(ARDUINO_ARCH_MFL)
|
||||
#include "../GD32_MFL/Servo.h"
|
||||
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
|
||||
#include "../STM32F1/Servo.h"
|
||||
#elif defined(ARDUINO_ARCH_STM32)
|
||||
|
|
|
|||
|
|
@ -383,7 +383,7 @@
|
|||
#define BOARD_CHITU3D_V6 5036 // Chitu3D TronXY X5SA V6 Board (STM32F103ZE)
|
||||
#define BOARD_CHITU3D_V9 5037 // Chitu3D TronXY X5SA V9 Board (STM32F103ZE)
|
||||
#define BOARD_CREALITY_V4 5038 // Creality v4.x (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V422 5039 // Creality v4.2.2 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V422 5039 // Creality v4.2.2 (STM32F103RC / STM32F103RE) ... GD32 Variant Below!
|
||||
#define BOARD_CREALITY_V423 5040 // Creality v4.2.3 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V425 5041 // Creality v4.2.5 (STM32F103RC / STM32F103RE)
|
||||
#define BOARD_CREALITY_V427 5042 // Creality v4.2.7 (STM32F103RC / STM32F103RE)
|
||||
|
|
@ -552,12 +552,18 @@
|
|||
#define BOARD_AQUILA_V101 7200 // Voxelab Aquila V1.0.0/V1.0.1/V1.0.2/V1.0.3 as found in the Voxelab Aquila X2 and C2
|
||||
#define BOARD_CREALITY_ENDER2P_V24S4 7201 // Creality Ender 2 Pro v2.4.S4_170 (HC32f460kcta)
|
||||
|
||||
//
|
||||
// GD32 ARM Cortex-M4
|
||||
//
|
||||
|
||||
#define BOARD_CREALITY_V422_GD32_MFL 7300 // Creality V4.2.2 MFL (GD32F303RE) ... STM32 Variant Above!
|
||||
|
||||
//
|
||||
// Raspberry Pi
|
||||
//
|
||||
|
||||
#define BOARD_RP2040 6200 // Generic RP2040 Test board
|
||||
#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
|
||||
#define BOARD_RP2040 6200 // Generic RP2040 Test board
|
||||
#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
|
||||
|
||||
//
|
||||
// Custom board
|
||||
|
|
|
|||
|
|
@ -241,10 +241,10 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L
|
|||
#error "SERIAL_XON_XOFF and SERIAL_STATS_* features not supported on USB-native AVR devices."
|
||||
#endif
|
||||
|
||||
// Serial DMA is only available for some STM32 MCUs and HC32
|
||||
// Serial DMA is only available for some STM32 MCUs, HC32 and GD32
|
||||
#if ENABLED(SERIAL_DMA)
|
||||
#ifdef ARDUINO_ARCH_HC32
|
||||
// checks for HC32 are located in HAL/HC32/inc/SanityCheck.h
|
||||
#if ANY(ARDUINO_ARCH_HC32, ARDUINO_ARCH_MFL)
|
||||
// See HAL/.../inc/SanityCheck.h
|
||||
#elif DISABLED(HAL_STM32) || NONE(STM32F0xx, STM32F1xx, STM32F2xx, STM32F4xx, STM32F7xx, STM32H7xx)
|
||||
#error "SERIAL_DMA is only available for some STM32 MCUs and requires HAL/STM32."
|
||||
#elif !defined(HAL_UART_MODULE_ENABLED) || defined(HAL_UART_MODULE_ONLY)
|
||||
|
|
|
|||
|
|
@ -696,9 +696,16 @@
|
|||
#warning "Don't forget to update your TFT settings in Configuration.h."
|
||||
#endif
|
||||
|
||||
#if ENABLED(EMIT_CREALITY_422_WARNING) && DISABLED(NO_CREALITY_422_DRIVER_WARNING)
|
||||
// Driver labels: A=TMC2208, B=TMC2209, C=HR4988, E=A4988, H=TMC2225, H8=HR4988
|
||||
#warning "Creality 4.2.2 boards come with a variety of stepper drivers. Check the board label (typically on SD Card module) and set the correct *_DRIVER_TYPE! (A/H: TMC2208_STANDALONE B: TMC2209_STANDALONE C/E/H8: A4988). (Define NO_CREALITY_422_DRIVER_WARNING to suppress this warning.)"
|
||||
#if ENABLED(EMIT_CREALITY_422_WARNING)
|
||||
#if DISABLED(NO_CREALITY_422_MCU_WARNING)
|
||||
#warning "Double-check your 4.2.2 board for STM32 / GD32. Use BOARD_CREALITY_V422 or BOARD_CREALITY_V422_GD32_MFL as appropriate for your MCU."
|
||||
#warning "GD32 Serial Ports are numbered starting from 0. STM32 Serial Ports are numbered starting from 1."
|
||||
#warning "(Define NO_CREALITY_422_MCU_WARNING to suppress these warnings.)"
|
||||
#endif
|
||||
#if DISABLED(NO_CREALITY_422_DRIVER_WARNING)
|
||||
// Driver labels: A=TMC2208, B=TMC2209, C=HR4988, E=A4988, H=TMC2225, H8=HR4988
|
||||
#warning "Creality 4.2.2 boards come with a variety of stepper drivers. Check the board label (typically on SD Card module) and set the correct *_DRIVER_TYPE! (A/H: TMC2208_STANDALONE B: TMC2209_STANDALONE C/E/H8: A4988). (Define NO_CREALITY_422_DRIVER_WARNING to suppress this warning.)"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(PRINTCOUNTER_SYNC)
|
||||
|
|
|
|||
|
|
@ -199,7 +199,7 @@ u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_sw_spi = { u8g_dev_st7920_128x64_HAL_4x_f
|
|||
U8G_PB_DEV(u8g_dev_st7920_128x64_HAL_hw_spi, LCD_PIXEL_WIDTH, LCD_PIXEL_HEIGHT, PAGE_HEIGHT, u8g_dev_st7920_128x64_HAL_fn, U8G_COM_ST7920_HAL_HW_SPI);
|
||||
u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_hw_spi = { u8g_dev_st7920_128x64_HAL_4x_fn, &u8g_dev_st7920_128x64_HAL_4x_pb, U8G_COM_ST7920_HAL_HW_SPI };
|
||||
|
||||
#if NONE(__AVR__, ARDUINO_ARCH_STM32, ARDUINO_ARCH_ESP32) || defined(U8G_HAL_LINKS)
|
||||
#if NONE(__AVR__, ARDUINO_ARCH_STM32, ARDUINO_ARCH_ESP32, ARDUINO_ARCH_MFL) || defined(U8G_HAL_LINKS)
|
||||
// Also use this device for HAL version of RRD class. This results in the same device being used
|
||||
// for the ST7920 for HAL systems no matter what is selected in marlinui_DOGM.h.
|
||||
u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = { u8g_dev_st7920_128x64_HAL_4x_fn, &u8g_dev_st7920_128x64_HAL_4x_pb, U8G_COM_ST7920_HAL_SW_SPI };
|
||||
|
|
|
|||
|
|
@ -25,7 +25,7 @@
|
|||
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ANY(__AVR__, ARDUINO_ARCH_STM32, ARDUINO_ARCH_ESP32)
|
||||
#if ANY(__AVR__, ARDUINO_ARCH_STM32, ARDUINO_ARCH_ESP32, ARDUINO_ARCH_MFL)
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
|
|
@ -193,4 +193,4 @@ u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = { u8g_dev_rrd_st7920_128x64_fn, &u8
|
|||
#endif
|
||||
|
||||
#endif // IS_U8GLIB_ST7920
|
||||
#endif // __AVR__ || ARDUINO_ARCH_STM32 || ARDUINO_ARCH_ESP32
|
||||
#endif // __AVR__ || ARDUINO_ARCH_STM32 || ARDUINO_ARCH_ESP32 || ARDUINO_ARCH_MFL
|
||||
|
|
|
|||
|
|
@ -48,7 +48,7 @@
|
|||
#ifdef __STM32F1__
|
||||
#define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0)
|
||||
#define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0)
|
||||
#elif defined(STM32F1) || defined(STM32F4) || defined(ARDUINO_ARCH_HC32)
|
||||
#elif ANY(STM32F1, STM32F4, ARDUINO_ARCH_HC32, ARDUINO_ARCH_MFL)
|
||||
#define SDA_IN() SET_INPUT(IIC_EEPROM_SDA)
|
||||
#define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA)
|
||||
#endif
|
||||
|
|
|
|||
37
Marlin/src/pins/gd32f3/pins_CREALITY_V422_GD32_MFL.h
Normal file
37
Marlin/src/pins/gd32f3/pins_CREALITY_V422_GD32_MFL.h
Normal file
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* 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
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Creality MFL GD32 V4.2.2 (GD32F303RE) board pin assignments
|
||||
*/
|
||||
|
||||
#define ALLOW_GD32F3
|
||||
|
||||
#ifndef BOARD_INFO_NAME
|
||||
#define BOARD_INFO_NAME "Creality V4.2.2 MFL"
|
||||
#endif
|
||||
#ifndef DEFAULT_MACHINE_NAME
|
||||
#define DEFAULT_MACHINE_NAME "Ender-3 MFL"
|
||||
#endif
|
||||
|
||||
#include "../stm32f1/pins_CREALITY_V4.h"
|
||||
|
|
@ -964,6 +964,13 @@
|
|||
#elif MB(CREALITY_ENDER2P_V24S4)
|
||||
#include "hc32f4/pins_CREALITY_ENDER2P_V24S4.h" // HC32F460 env:HC32F460C_e2p24s4
|
||||
|
||||
//
|
||||
// GD32 ARM Cortex-M4
|
||||
//
|
||||
|
||||
#elif MB(CREALITY_V422_GD32_MFL)
|
||||
#include "gd32f3/pins_CREALITY_V422_GD32_MFL.h" // GD32F303RE env:GD32F303RE_creality_mfl
|
||||
|
||||
//
|
||||
// Raspberry Pi RP2040
|
||||
//
|
||||
|
|
|
|||
|
|
@ -27,6 +27,8 @@
|
|||
|
||||
#if TARGET_LPC1768
|
||||
#define ANALOG_OK(PN) (WITHIN(PN, P0_02, P0_03) || WITHIN(PN, P0_23, P0_26) || WITHIN(PN, P1_30, P1_31))
|
||||
#elif ARDUINO_ARCH_MFL
|
||||
#define ANALOG_OK(PN) (WITHIN(PN, 0, 7) || WITHIN(PN, 16, 17) || WITHIN(PN, 32, 37))
|
||||
#else
|
||||
#define ANALOG_OK(PN) WITHIN(PN, 0, NUM_ANALOG_INPUTS - 1)
|
||||
#endif
|
||||
|
|
|
|||
|
|
@ -23,13 +23,16 @@
|
|||
#define ENV_VALIDATE_H
|
||||
|
||||
#if NOT_TARGET(__STM32F1__, STM32F1)
|
||||
#if DISABLED(ALLOW_STM32F4)
|
||||
#if NONE(ALLOW_STM32F4, ALLOW_GD32F3)
|
||||
#error "Oops! Select an STM32F1 board in 'Tools > Board.'"
|
||||
#elif NOT_TARGET(STM32F4)
|
||||
#elif ENABLED(ALLOW_STM32F4) && NOT_TARGET(STM32F4)
|
||||
#error "Oops! Select an STM32F4 board in 'Tools > Board.'"
|
||||
#elif ENABLED(ALLOW_GD32F3) && NOT_TARGET(ARDUINO_ARCH_MFL)
|
||||
#error "Oops! Make sure you have a GD32F3 MFL environment selected."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#undef ALLOW_STM32F4
|
||||
#undef ALLOW_GD32F3
|
||||
|
||||
#endif
|
||||
|
|
|
|||
|
|
@ -58,12 +58,13 @@ Every new HAL opens up a world of hardware. At this time we need HALs for RP2040
|
|||
[Teensy++ 2.0](//www.microchip.com/en-us/product/AT90USB1286)|AT90USB1286|Printrboard
|
||||
[Arduino Due](//www.arduino.cc/en/Guide/ArduinoDue)|SAM3X8E|RAMPS-FD, RADDS, RAMPS4DUE
|
||||
[ESP32](//github.com/espressif/arduino-esp32)|ESP32|FYSETC E4, E4d@BOX, MRR
|
||||
[GD32](//www.gigadevice.com/)|GD32 ARM Cortex-M4|Creality MFL GD32 V4.2.2
|
||||
[HC32](//www.huazhoucn.com/)|HC32|Ender-2 Pro, Voxelab Aquila
|
||||
[LPC1768](//www.nxp.com/products/processors-and-microcontrollers/arm-microcontrollers/general-purpose-mcus/lpc1700-cortex-m3/512-kb-flash-64-kb-sram-ethernet-usb-lqfp100-package:LPC1768FBD100)|ARM® Cortex-M3|MKS SBASE, Re-ARM, Selena Compact
|
||||
[LPC1769](//www.nxp.com/products/processors-and-microcontrollers/arm-microcontrollers/general-purpose-mcus/lpc1700-cortex-m3/512-kb-flash-64-kb-sram-ethernet-usb-lqfp100-package:LPC1769FBD100)|ARM® Cortex-M3|Smoothieboard, Azteeg X5 mini, TH3D EZBoard
|
||||
[Pico RP2040](//www.raspberrypi.com/documentation/microcontrollers/pico-series.html)|Dual Cortex M0+|BigTreeTech SKR Pico
|
||||
[STM32F103](//www.st.com/en/microcontrollers-microprocessors/stm32f103.html)|ARM® Cortex-M3|Malyan M200, GTM32 Pro, MKS Robin, BTT SKR Mini
|
||||
[STM32F401](//www.st.com/en/microcontrollers-microprocessors/stm32f401.html)|ARM® Cortex-M4|ARMED, Rumba32, SKR Pro, Lerdge, FYSETC S6, Artillery Ruby
|
||||
[Pico RP2040](//www.raspberrypi.com/documentation/microcontrollers/pico-series.html)|Dual Cortex M0+|BigTreeTech SKR Pico
|
||||
[STM32F7x6](//www.st.com/en/microcontrollers-microprocessors/stm32f7x6.html)|ARM® Cortex-M7|The Borg, RemRam V1
|
||||
[STM32G0B1RET6](//www.st.com/en/microcontrollers-microprocessors/stm32g0x1.html)|ARM® Cortex-M0+|BigTreeTech SKR mini E3 V3.0
|
||||
[STM32H743xIT6](//www.st.com/en/microcontrollers-microprocessors/stm32h743-753.html)|ARM® Cortex-M7|BigTreeTech SKR V3.0, SKR EZ V3.0, SKR SE BX V2.0/V3.0
|
||||
|
|
|
|||
17
buildroot/tests/GD32F303RE_creality_mfl
Executable file
17
buildroot/tests/GD32F303RE_creality_mfl
Executable file
|
|
@ -0,0 +1,17 @@
|
|||
#!/usr/bin/env bash
|
||||
#
|
||||
# Build tests for GD32F303RE_creality_mfl
|
||||
#
|
||||
|
||||
# exit on first failure
|
||||
set -e
|
||||
|
||||
restore_configs
|
||||
opt_set MOTHERBOARD BOARD_CREALITY_V422_GD32_MFL SERIAL_PORT 0
|
||||
opt_enable EEPROM_SETTINGS SDSUPPORT EMERGENCY_PARSER FAN_SOFT_PWM PINS_DEBUGGING
|
||||
opt_add NO_CREALITY_422_DRIVER_WARNING
|
||||
opt_add NO_AUTO_ASSIGN_WARNING
|
||||
exec_test $1 $2 "Creality V4.2.2 MFL GD32 Default Configuration" "$3"
|
||||
|
||||
# cleanup
|
||||
restore_configs
|
||||
47
ini/gd32.ini
Normal file
47
ini/gd32.ini
Normal file
|
|
@ -0,0 +1,47 @@
|
|||
#
|
||||
# Marlin Firmware
|
||||
# PlatformIO Configuration File
|
||||
#
|
||||
|
||||
####################################
|
||||
#
|
||||
# HAL/MFL GD32 Environments
|
||||
#
|
||||
####################################
|
||||
|
||||
[gd32_base]
|
||||
platform = https://github.com/bmourit/platform-mfl/archive/refs/tags/V1.0.2.zip
|
||||
board_build.core = gd32
|
||||
build_src_filter = ${common.default_src_filter} +<src/HAL/GD32_MFL> +<src/HAL/shared/backtrace>
|
||||
build_unflags = -std=gnu++11 -std=gnu++14 -std=gnu++17
|
||||
build_flags = -std=gnu++23
|
||||
-DARDUINO_ARCH_MFL
|
||||
-DPLATFORM_M997_SUPPORT
|
||||
-DTIMER_IRQ_PRIORITY=12
|
||||
-DADC_RESOLUTION=12
|
||||
-DCORE_DEBUG
|
||||
-Wno-deprecated-declarations
|
||||
-Wno-volatile
|
||||
extra_scripts = ${common.extra_scripts}
|
||||
|
||||
#
|
||||
# Creality (GD32F303RE)
|
||||
#
|
||||
[env:GD32F303RE_creality_mfl]
|
||||
extends = gd32_base
|
||||
board = mfl_creality_422
|
||||
board_build.offset = 0x7000
|
||||
board_build.rename = firmware-{time}.bin
|
||||
board_upload.offset_address = 0x08007000
|
||||
build_flags = ${gd32_base.build_flags}
|
||||
-DMCU_GD32F303RE
|
||||
-DGD32F303RE
|
||||
-DTIMER_TONE=2
|
||||
-DSS_TIMER=3
|
||||
-DTIMER_SERVO=4
|
||||
-DTRANSFER_CLOCK_DIV=8
|
||||
-fsingle-precision-constant
|
||||
extra_scripts = ${gd32_base.extra_scripts}
|
||||
buildroot/share/PlatformIO/scripts/offset_and_rename.py
|
||||
|
||||
monitor_speed = 115200
|
||||
|
|
@ -22,6 +22,7 @@ extra_configs =
|
|||
ini/esp32.ini
|
||||
ini/features.ini
|
||||
ini/hc32.ini
|
||||
ini/gd32.ini
|
||||
ini/lpc176x.ini
|
||||
ini/native.ini
|
||||
ini/samd21.ini
|
||||
|
|
|
|||
Loading…
Add table
Add a link
Reference in a new issue