Merge upstream changes from Marlin 2.1.1

This commit is contained in:
Stefan Kalscheuer
2022-09-03 09:23:32 +02:00
parent 626283aadb
commit 986e416c7f
1610 changed files with 73839 additions and 40857 deletions

View File

@@ -108,13 +108,14 @@
#if ENABLED(MARLIN_DEV_MODE)
void dump_delay_accuracy_check() {
auto report_call_time = [](PGM_P const name, PGM_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) {
auto report_call_time = [](FSTR_P const name, FSTR_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) {
SERIAL_ECHOPGM("Calling ");
SERIAL_ECHOPGM_P(name);
SERIAL_ECHOF(name);
SERIAL_ECHOLNPGM(" for ", cycles);
SERIAL_ECHOPGM_P(unit);
SERIAL_ECHOF(unit);
SERIAL_ECHOLNPGM(" took: ", total);
SERIAL_ECHOPGM_P(unit);
SERIAL_CHAR(' ');
SERIAL_ECHOF(unit);
if (do_flush) SERIAL_FLUSHTX();
};
@@ -126,41 +127,42 @@
constexpr uint32_t testValues[] = { 1, 5, 10, 20, 50, 100, 150, 200, 350, 500, 750, 1000 };
for (auto i : testValues) {
s = micros(); DELAY_US(i); e = micros();
report_call_time(PSTR("delay"), PSTR("us"), i, e - s);
report_call_time(F("delay"), F("us"), i, e - s);
}
if (HW_REG(_DWT_CTRL)) {
static FSTR_P cyc = F("cycles");
static FSTR_P dcd = F("DELAY_CYCLES directly ");
for (auto i : testValues) {
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(i); e = HW_REG(_DWT_CYCCNT);
report_call_time(PSTR("runtime delay"), PSTR("cycles"), i, e - s);
report_call_time(F("runtime delay"), cyc, i, e - s);
}
// Measure the delay to call a real function compared to a function pointer
s = HW_REG(_DWT_CYCCNT); delay_dwt(1); e = HW_REG(_DWT_CYCCNT);
report_call_time(PSTR("delay_dwt"), PSTR("cycles"), 1, e - s);
static PGMSTR(dcd, "DELAY_CYCLES directly ");
report_call_time(F("delay_dwt"), cyc, 1, e - s);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 1); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 1, e - s, false);
report_call_time(dcd, cyc, 1, e - s, false);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES( 5); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 5, e - s, false);
report_call_time(dcd, cyc, 5, e - s, false);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(10); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 10, e - s, false);
report_call_time(dcd, cyc, 10, e - s, false);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(20); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 20, e - s, false);
report_call_time(dcd, cyc, 20, e - s, false);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(50); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 50, e - s, false);
report_call_time(dcd, cyc, 50, e - s, false);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(100); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 100, e - s, false);
report_call_time(dcd, cyc, 100, e - s, false);
s = HW_REG(_DWT_CYCCNT); DELAY_CYCLES(200); e = HW_REG(_DWT_CYCCNT);
report_call_time(dcd, PSTR("cycles"), 200, e - s, false);
report_call_time(dcd, cyc, 200, e - s, false);
}
}
#endif // MARLIN_DEV_MODE
@@ -170,7 +172,7 @@
void calibrate_delay_loop() {}
#if ENABLED(MARLIN_DEV_MODE)
void dump_delay_accuracy_check() { SERIAL_ECHOPGM_P(PSTR("N/A on this platform")); }
void dump_delay_accuracy_check() { SERIAL_ECHOPGM("N/A on this platform"); }
#endif
#endif

View File

@@ -92,6 +92,12 @@ void calibrate_delay_loop();
#define DELAY_CYCLES(X) do { SmartDelay<IS_CONSTEXPR(X), IS_CONSTEXPR(X) ? X : 0> _smrtdly_X(X); } while(0)
#if GCC_VERSION <= 70000
#define DELAY_CYCLES_VAR(X) DelayCycleFnc(X)
#else
#define DELAY_CYCLES_VAR DELAY_CYCLES
#endif
// For delay in microseconds, no smart delay selection is required, directly call the delay function
// Teensy compiler is too old and does not accept smart delay compile-time / run-time selection correctly
#define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL))
@@ -160,6 +166,8 @@ void calibrate_delay_loop();
// Delay in microseconds
#define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL))
#define DELAY_CYCLES_VAR DELAY_CYCLES
#elif defined(ESP32) || defined(__PLAT_LINUX__) || defined(__PLAT_NATIVE_SIM__)
// DELAY_CYCLES specified inside platform
@@ -200,9 +208,12 @@ void calibrate_delay_loop();
#endif
#if ENABLED(DELAY_NS_ROUND_DOWN)
#define DELAY_NS(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL) / 1000UL) // floor
#define _NS_TO_CYCLES(x) ( (x) * ((F_CPU) / 1000000UL) / 1000UL) // floor
#elif ENABLED(DELAY_NS_ROUND_CLOSEST)
#define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 500) / 1000UL) // round
#define _NS_TO_CYCLES(x) (((x) * ((F_CPU) / 1000000UL) + 500) / 1000UL) // round
#else
#define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 999) / 1000UL) // "ceil"
#define _NS_TO_CYCLES(x) (((x) * ((F_CPU) / 1000000UL) + 999) / 1000UL) // "ceil"
#endif
#define DELAY_NS(x) DELAY_CYCLES(_NS_TO_CYCLES(x))
#define DELAY_NS_VAR(x) DELAY_CYCLES_VAR(_NS_TO_CYCLES(x))

View File

@@ -0,0 +1,36 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2022 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/>.
*
*/
/**
* HAL/shared/HAL.cpp
*/
#include "../../inc/MarlinConfig.h"
MarlinHAL hal;
#if ENABLED(SOFT_RESET_VIA_SERIAL)
// Global for use by e_parser.h
void HAL_reboot() { hal.reboot(); }
#endif

View File

@@ -1,139 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
/**
* Software L6470 SPI functions originally from Arduino Sd2Card Library
* Copyright (c) 2009 by William Greiman
*/
#include "../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "Delay.h"
#include "../../core/serial.h"
#include "../../libs/L64XX/L64XX_Marlin.h"
// Make sure GCC optimizes this file.
// Note that this line triggers a bug in GCC which is fixed by casting.
// See the note below.
#pragma GCC optimize (3)
// run at ~4Mhz
inline uint8_t L6470_SpiTransfer_Mode_0(uint8_t b) { // using Mode 0
for (uint8_t bits = 8; bits--;) {
WRITE(L6470_CHAIN_MOSI_PIN, b & 0x80);
b <<= 1; // little setup time
WRITE(L6470_CHAIN_SCK_PIN, HIGH);
DELAY_NS(125); // 10 cycles @ 84mhz
b |= (READ(L6470_CHAIN_MISO_PIN) != 0);
WRITE(L6470_CHAIN_SCK_PIN, LOW);
DELAY_NS(125); // 10 cycles @ 84mhz
}
return b;
}
inline uint8_t L6470_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3
for (uint8_t bits = 8; bits--;) {
WRITE(L6470_CHAIN_SCK_PIN, LOW);
WRITE(L6470_CHAIN_MOSI_PIN, b & 0x80);
DELAY_NS(125); // 10 cycles @ 84mhz
WRITE(L6470_CHAIN_SCK_PIN, HIGH);
DELAY_NS(125); // Need more delay for fast CPUs
b <<= 1; // little setup time
b |= (READ(L6470_CHAIN_MISO_PIN) != 0);
}
DELAY_NS(125); // 10 cycles @ 84mhz
return b;
}
/**
* L64XX methods for SPI init and transfer
*/
void L64XX_Marlin::spi_init() {
OUT_WRITE(L6470_CHAIN_SS_PIN, HIGH);
OUT_WRITE(L6470_CHAIN_SCK_PIN, HIGH);
OUT_WRITE(L6470_CHAIN_MOSI_PIN, HIGH);
SET_INPUT(L6470_CHAIN_MISO_PIN);
#if PIN_EXISTS(L6470_BUSY)
SET_INPUT(L6470_BUSY_PIN);
#endif
OUT_WRITE(L6470_CHAIN_MOSI_PIN, HIGH);
}
uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) {
// First device in chain has data sent last
extDigitalWrite(ss_pin, LOW);
DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
const uint8_t data_out = L6470_SpiTransfer_Mode_3(data);
ENABLE_ISRS(); // Enable interrupts
extDigitalWrite(ss_pin, HIGH);
return data_out;
}
uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain_position) {
uint8_t data_out = 0;
// first device in chain has data sent last
extDigitalWrite(ss_pin, LOW);
for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted
DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP));
ENABLE_ISRS(); // Enable interrupts
if (i == chain_position) data_out = temp;
}
extDigitalWrite(ss_pin, HIGH);
return data_out;
}
/**
* Platform-supplied L6470 buffer transfer method
*/
void L64XX_Marlin::transfer(uint8_t L6470_buf[], const uint8_t length) {
// First device in chain has its data sent last
if (spi_active) { // Interrupted SPI transfer so need to
WRITE(L6470_CHAIN_SS_PIN, HIGH); // guarantee min high of 650ns
DELAY_US(1);
}
WRITE(L6470_CHAIN_SS_PIN, LOW);
for (uint8_t i = length; i >= 1; i--)
L6470_SpiTransfer_Mode_3(uint8_t(L6470_buf[i]));
WRITE(L6470_CHAIN_SS_PIN, HIGH);
}
#pragma GCC reset_options
#endif // HAS_L64XX

View File

@@ -39,7 +39,7 @@
#define DISABLED(V...) DO(DIS,&&,V)
#undef _BV
#define _BV(b) (1UL << (b))
#define _BV(b) (1 << (b))
#ifndef SBI
#define SBI(A,B) (A |= _BV(B))
#endif
@@ -83,7 +83,14 @@
#endif
#ifndef FORCE_INLINE
#define FORCE_INLINE inline __attribute__((always_inline))
#define FORCE_INLINE __attribute__((always_inline)) inline
#endif
#include "progmem.h"
class __FlashStringHelper;
typedef const __FlashStringHelper* FSTR_P;
#ifndef FPSTR
#define FPSTR(S) (reinterpret_cast<FSTR_P>(S))
#endif
#define FTOP(S) (reinterpret_cast<const char*>(S))

View File

@@ -19,7 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "HAL_MinSerial.h"
#include "MinSerial.h"
#if ENABLED(POSTMORTEM_DEBUGGING)

View File

@@ -25,7 +25,7 @@
#include "unwinder.h"
#include "unwmemaccess.h"
#include "../HAL_MinSerial.h"
#include "../MinSerial.h"
#include <stdarg.h>
// Dump a backtrace entry

View File

@@ -135,11 +135,11 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
while ((instruction = UnwTabGetNextInstruction(cb, ucb)) != -1) {
if ((instruction & 0xC0) == 0x00) { // ARM_EXIDX_CMD_DATA_POP
/* vsp = vsp + (xxxxxx << 2) + 4 */
/* vsp += (xxxxxx << 2) + 4 */
ucb->vrs[13] += ((instruction & 0x3F) << 2) + 4;
}
else if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH
/* vsp = vsp - (xxxxxx << 2) - 4 */
/* vsp -= (xxxxxx << 2) - 4 */
ucb->vrs[13] -= ((instruction & 0x3F) << 2) - 4;
}
else if ((instruction & 0xF0) == 0x80) {

View File

@@ -41,7 +41,7 @@
#define START_FLASH_ADDR 0x00000000
#define END_FLASH_ADDR 0x00080000
#elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx)
#elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx) || defined(STM32G0xx)
// For STM32F103ZET6/STM32F103VET6/STM32F0xx
// SRAM (0x20000000 - 0x20010000) (64kb)

View File

@@ -54,7 +54,7 @@
#include "exception_hook.h"
#include "../backtrace/backtrace.h"
#include "../HAL_MinSerial.h"
#include "../MinSerial.h"
#define HW_REG(X) (*((volatile unsigned long *)(X)))
@@ -101,7 +101,7 @@ struct __attribute__((packed)) ContextSavedFrame {
uint32_t ELR;
};
#if DISABLED(STM32F0xx)
#if NONE(STM32F0xx, STM32G0xx)
extern "C"
__attribute__((naked)) void CommonHandler_ASM() {
__asm__ __volatile__ (
@@ -221,7 +221,7 @@ bool resume_from_fault() {
// So we'll just need to refresh the watchdog for a while and then stop for the system to reboot
uint32_t last = start;
while (PENDING(last, end)) {
watchdog_refresh();
hal.watchdog_refresh();
while (millis() == last) { /* nada */ }
last = millis();
MinSerial::TX('.');

View File

@@ -49,7 +49,7 @@ public:
// Write one or more bytes of data
// Return 'true' on write error
static inline bool write_data(const int pos, const uint8_t *value, const size_t size=sizeof(uint8_t)) {
static bool write_data(const int pos, const uint8_t *value, const size_t size=sizeof(uint8_t)) {
int data_pos = pos;
uint16_t crc = 0;
return write_data(data_pos, value, size, &crc);
@@ -57,11 +57,11 @@ public:
// Write a single byte of data
// Return 'true' on write error
static inline bool write_data(const int pos, const uint8_t value) { return write_data(pos, &value); }
static bool write_data(const int pos, const uint8_t value) { return write_data(pos, &value); }
// Read one or more bytes of data
// Return 'true' on read error
static inline bool read_data(const int pos, uint8_t *value, const size_t size=1) {
static bool read_data(const int pos, uint8_t *value, const size_t size=1) {
int data_pos = pos;
uint16_t crc = 0;
return read_data(data_pos, value, size, &crc);

View File

@@ -26,6 +26,6 @@
/**
* Math helper functions for 32 bit CPUs
*/
static FORCE_INLINE uint32_t MultiU32X24toH32(uint32_t longIn1, uint32_t longIn2) {
FORCE_INLINE static uint32_t MultiU32X24toH32(uint32_t longIn1, uint32_t longIn2) {
return ((uint64_t)longIn1 * longIn2 + 0x00800000) >> 24;
}

View File

@@ -38,7 +38,8 @@
#define PSTR(str) (str)
#endif
#ifndef F
#define F(str) (str)
class __FlashStringHelper;
#define F(str) (reinterpret_cast<const __FlashStringHelper *>(PSTR(str)))
#endif
#ifndef _SFR_BYTE
#define _SFR_BYTE(n) (n)
@@ -110,7 +111,7 @@
#define strrchr_P(str, c) strrchr((str), (c))
#endif
#ifndef strsep_P
#define strsep_P(strp, delim) strsep((strp), (delim))
#define strsep_P(pstr, delim) strsep((pstr), (delim))
#endif
#ifndef strspn_P
#define strspn_P(str, chrs) strspn((str), (chrs))

View File

@@ -65,7 +65,7 @@ uint8_t ServoCount = 0; // the total number of attached
/************ static functions common to all instances ***********************/
static boolean isTimerActive(timer16_Sequence_t timer) {
static bool anyTimerChannelActive(const timer16_Sequence_t timer) {
// returns true if any servo is active on this timer
LOOP_L_N(channel, SERVOS_PER_TIMER) {
if (SERVO(timer, channel).Pin.isActive)
@@ -101,17 +101,18 @@ int8_t Servo::attach(const int inPin, const int inMin, const int inMax) {
max = (MAX_PULSE_WIDTH - inMax) / 4;
// initialize the timer if it has not already been initialized
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!isTimerActive(timer)) initISR(timer);
servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
const timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!anyTimerChannelActive(timer)) initISR(timer);
servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for anyTimerChannelActive
return servoIndex;
}
void Servo::detach() {
servo_info[servoIndex].Pin.isActive = false;
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!isTimerActive(timer)) finISR(timer);
const timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!anyTimerChannelActive(timer)) finISR(timer);
//pinMode(servo_info[servoIndex].Pin.nbr, INPUT); // set servo pin to input
}
void Servo::write(int value) {

View File

@@ -70,10 +70,10 @@
#define ticksToUs(_ticks) (unsigned(_ticks) * (SERVO_TIMER_PRESCALER) / clockCyclesPerMicrosecond())
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / (SERVOS_PER_TIMER))) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servo_info[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_INDEX_TO_TIMER(_servo_nbr) timer16_Sequence_t(_servo_nbr / (SERVOS_PER_TIMER)) // the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // servo index by timer and channel
#define SERVO(_timer,_channel) servo_info[SERVO_INDEX(_timer,_channel)] // servo class by timer and channel
// Types
@@ -94,5 +94,5 @@ extern ServoInfo_t servo_info[MAX_SERVOS];
// Public functions
extern void initISR(timer16_Sequence_t timer);
extern void finISR(timer16_Sequence_t timer);
void initISR(const timer16_Sequence_t timer_index);
void finISR(const timer16_Sequence_t timer_index);