🎨 Spelling corrections (#28026)

This commit is contained in:
Thijs Triemstra 2025-09-06 05:14:09 +02:00 committed by GitHub
parent 7526309ccf
commit 52ea53a3dd
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
38 changed files with 56 additions and 56 deletions

View file

@ -4004,7 +4004,7 @@
#endif
/**
* M115 - Report capabilites. Disable to save ~1150 bytes of flash.
* M115 - Report capabilities. Disable to save ~1150 bytes of flash.
* Some hosts (and serial TFT displays) rely on this feature.
*/
#define CAPABILITIES_REPORT

View file

@ -523,7 +523,7 @@ static bool udd_ep_interrupt(void);
* \internal
* \brief Function called by UOTGHS interrupt to manage USB Device interrupts
*
* USB Device interrupt events are splited in three parts:
* USB Device interrupt events are split in three parts:
* - USB line events (SOF, reset, suspend, resume, wakeup)
* - control endpoint events (setup reception, end of data transfer, underflow, overflow, stall)
* - bulk/interrupt/isochronous endpoints events (end of data transfer)
@ -1567,7 +1567,7 @@ static void udd_ctrl_out_received(void)
udd_ctrl_payload_buf_cnt))) {
// End of reception because it is a short packet
// Before send ZLP, call intermediate callback
// in case of data receiv generate a stall
// in case of data receive generate a stall
udd_g_ctrlreq.payload_size = udd_ctrl_payload_buf_cnt;
if (NULL != udd_g_ctrlreq.over_under_run) {
if (!udd_g_ctrlreq.over_under_run()) {
@ -1808,7 +1808,7 @@ static void udd_ep_trans_done(udd_ep_id_t ep)
}
if (ptr_job->buf_cnt != ptr_job->buf_size) {
// Need to send or receiv other data
// Need to send or receive other data
next_trans = ptr_job->buf_size - ptr_job->buf_cnt;
if (UDD_ENDPOINT_MAX_TRANS < next_trans) {

View file

@ -73,7 +73,7 @@ public:
// Interrupt handler
void handle_interrupts();
// Varaible stored parameters
// Variable stored parameters
auto get_scr(uint16_t rca, uint32_t* scr) -> SDIO_Error_Type;
auto store_cid() -> SDIO_Error_Type;
auto store_csd() -> SDIO_Error_Type;

View file

@ -49,7 +49,7 @@ extern Timer0 step_timer;
* See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information.
*
* NOTE: If the 'constexpr' requirement is ever lifted, TIMER0_BASE_FREQUENCY could
* be used instead. Tho this would probably not make any noticable difference.
* be used instead. Tho this would probably not make any noticeable difference.
*/
#define HAL_TIMER_RATE F_PCLK1

View file

@ -112,7 +112,7 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
void MarlinHAL::watchdog_init() {
#if DISABLED(DISABLE_WATCHDOG_INIT)
static_assert(WDT_TIMEOUT_US > 1000, "WDT Timout is too small, aborting");
static_assert(WDT_TIMEOUT_US > 1000, "WDT Timeout is too small, aborting");
watchdog_enable(WDT_TIMEOUT_US/1000, true);
#endif
}

View file

@ -176,7 +176,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
tc->COUNT32.CTRLA.reg |= TC_CTRLA_WAVEGEN_MFRQ;
//set prescaler
//the clock normally counts at the GCLK_TC frequency, but we can set it to divide that frequency to slow it down
//you can use different prescaler divisons here like TC_CTRLA_PRESCALER_DIV1 to get a different range
//you can use different prescaler divisions here like TC_CTRLA_PRESCALER_DIV1 to get a different range
tc->COUNT32.CTRLA.reg |= TC_CTRLA_PRESCALER_DIV1 | TC_CTRLA_ENABLE; //it will divide GCLK_TC frequency by 1024
//set the compare-capture register.
//The counter will count up to this value (it's a 16bit counter so we use uint16_t)

View file

@ -209,7 +209,7 @@ HAL_HardwareSerial::HAL_HardwareSerial(void *peripheral) {
}
#endif
else { // else get the pins of the first peripheral occurence in PinMap
else { // else get the pins of the first peripheral occurrence in PinMap
_serial.pin_rx = pinmap_pin(peripheral, PinMap_UART_RX);
_serial.pin_tx = pinmap_pin(peripheral, PinMap_UART_TX);
}

View file

@ -131,7 +131,7 @@ uint16_t MarlinHAL::adc_result;
#include <STM32ADC.h>
// Init the AD in continuous capture mode
// Init the ADC in continuous capture mode
void MarlinHAL::adc_init() {
static const uint8_t adc_pins[] = {
OPTITEM(HAS_TEMP_ADC_0, TEMP_0_PIN )

View file

@ -15,7 +15,7 @@
#include "unwinder.h"
/** The maximum number of instructions to interpet in a function.
/** The maximum number of instructions to interpret in a function.
* Unwinding will be unconditionally stopped and UNWIND_EXHAUSTED returned
* if more than this number of instructions are interpreted in a single
* function without unwinding a stack frame. This prevents infinite loops

View file

@ -483,7 +483,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
// Check if the kill button was pressed and wait to ensure the signal is not noise
// typically caused by poor insulation and grounding on LCD cables.
// Lower numbers here will increase response time and therefore safety rating.
// It is recommended to set this as low as possibe without false triggers.
// It is recommended to set this as low as possible without false triggers.
// -------------------------------------------------------------------------------
#ifndef KILL_DELAY
#define KILL_DELAY 250

View file

@ -131,7 +131,7 @@ void EasythreedUI::loadButton() {
break;
case FS_PROCEED: {
// Feed or Retract just once. Hard abort all moves and return to idle on swicth release.
// Feed or Retract just once. Hard abort all moves and return to idle on switch release.
static bool flag = false;
if (READ(BTN_RETRACT) && READ(BTN_FEED)) { // Switch in center position (stop)
flag = false; // Restore flag to false

View file

@ -1162,7 +1162,7 @@ namespace MMU3 {
//
// Instead of doing a very long extrude as in PrusaFirmware,
// Marlin's own MMU2s code has a better approach to this by spinning
// the extruder indefinitelly...
// the extruder indefinitely...
//
// this ensures that while the MMU is pushing the filament,
// the extruder will keep rotating, preventing the filament to hit

View file

@ -115,12 +115,12 @@
void powerOn();
// Read from a MMU register (See gcode M707)
// @param address Address of register in hexidecimal
// @param address Address of register in hexadecimal
// @return true upon success
bool readRegister(uint8_t address);
// Write from a MMU register (See gcode M708)
// @param address Address of register in hexidecimal
// @param address Address of register in hexadecimal
// @param data Data to write to register
// @return true upon success
bool writeRegister(uint8_t address, uint16_t data);
@ -204,7 +204,7 @@
ErrorCode getLastErrorCode() const { return lastErrorCode; }
// @return the version of the connected MMU FW.
// In the future we'll return the trully detected FW version
// In the future we'll return the truly detected FW version
Version getMMUFWVersion() const {
if (state() == xState::Active) {
return { logic.mmuFwVersionMajor(), logic.mmuFwVersionMinor(), logic.mmuFwVersionRevision() };

View file

@ -60,7 +60,7 @@ namespace MMU3 {
return (i != errorCodesEnd) ? (i - errorCodes) : (errorCodesSize - 1);
}
// check that the searching algoritm works
// check that the searching algorithm works
// static_assert( FindErrorIndex(ERR_MECHANICAL_FINDA_DIDNT_TRIGGER) == 0);
// static_assert( FindErrorIndex(ERR_MECHANICAL_FINDA_FILAMENT_STUCK) == 1);
// static_assert( FindErrorIndex(ERR_MECHANICAL_FSENSOR_DIDNT_TRIGGER) == 2);

View file

@ -32,7 +32,7 @@
namespace MMU3 {
// Can be used to block printer's filament sensor handling - to avoid errorneous injecting of M600
// Can be used to block printer's filament sensor handling - to avoid erroneous injecting of M600
// while doing a toolchange with the MMU
// In case of "no filament sensor" these methods default to an empty implementation
class FSensorBlockRunout {

View file

@ -115,7 +115,7 @@ namespace protocol {
// A response message - responses are being sent from the MMU into the printer as a response to a request message.
struct ResponseMsg {
RequestMsg request; //!< response is always preceeded by the request message
RequestMsg request; //!< response is always preceded by the request message
ResponseMsgParamCodes paramCode; //!< code of the parameter
uint16_t paramValue; //!< value of the parameter
@ -157,7 +157,7 @@ namespace protocol {
// Protocol class is responsible for creating/decoding messages in Rx/Tx buffer
//
// Beware - in the decoding more, it is meant to be a statefull instance which works through public methods
// Beware - in the decoding more, it is meant to be a stateful instance which works through public methods
// processing one input byte per call.
class Protocol {
public:
@ -186,11 +186,11 @@ namespace protocol {
static uint8_t EncodeWriteRequest(uint8_t address, uint16_t value, uint8_t *txbuff);
// @return the maximum byte length necessary to encode a request message
// Beneficial in case of pre-allocating a buffer for enconding a RequestMsg.
// Beneficial in case of pre-allocating a buffer for encoding a RequestMsg.
static constexpr uint8_t MaxRequestSize() { return 13; }
// @return the maximum byte length necessary to encode a response message
// Beneficial in case of pre-allocating a buffer for enconding a ResponseMsg.
// Beneficial in case of pre-allocating a buffer for encoding a ResponseMsg.
static constexpr uint8_t MaxResponseSize() { return 14; }
// Encode generic response Command Accepted or Rejected

View file

@ -449,7 +449,7 @@ namespace MMU3 {
const uint8_t ei = PrusaErrorCodeIndex((ErrorCode)ec);
// This should be the equivelent of the switch..case above...
// This should be the equivalent of the switch..case above...
if ((uint8_t)ReportErrorHookState == (uint8_t)ReportErrorHookStates::RENDER_ERROR_SCREEN) {
KEEPALIVE_STATE(PAUSED_FOR_USER);
#if HAS_WIRED_LCD

View file

@ -33,7 +33,7 @@
* therefore the error codes have been extracted to one place.
*
* Please note the errors are intentionally coded as "negative" values (highest bit set),
* becase they are a complement to reporting the state of the high-level state machines -
* because they are a complement to reporting the state of the high-level state machines -
* positive values are considered as normal progress, negative values are errors.
*
* Please note, that multiple TMC errors can occur at once, thus they are defined as a bitmask of the higher byte.

View file

@ -114,7 +114,7 @@ typedef enum : uint16_t {
} err_num_t;
// Avr gcc has serious trouble understanding static data structures in PROGMEM
// and inadvertedly falls back to copying the whole structure into RAM (which is obviously unwanted).
// and inadvertently falls back to copying the whole structure into RAM (which is obviously unwanted).
// But since this file ought to be generated in the future from yaml prescription,
// it really makes no difference if there are "nice" data structures or plain arrays.
static const constexpr err_num_t errorCodes[] PROGMEM = {

View file

@ -1013,7 +1013,7 @@
TMC_REPORT("Supply (v)", TMC_VSUPPLY);
TMC_REPORT("Temp (°C)", TMC_TEMP);
TMC_REPORT("OT pre warn (°C)", TMC_OVERTEMP);
TMC_REPORT("OV theshold (v)", TMC_OVERVOLT_THD);
TMC_REPORT("OV threshold (v)", TMC_OVERVOLT_THD);
#endif
SERIAL_EOL();
}

View file

@ -94,7 +94,7 @@ void GcodeSuite::M706() {
* M707 [ A ]
*
* Parameters:
* A<hex> Address of register in hexidecimal
* A<hex> Address of register in hexadecimal
*
* Example:
* M707 A0x1b - Read a 8bit integer from register 0x1b and prints the result onto the serial line.
@ -115,7 +115,7 @@ void GcodeSuite::M707() {
* M708 [ A | X ]
*
* Parameters:
* A<hex> Address of register in hexidecimal
* A<hex> Address of register in hexadecimal
* X<int> Data to write (16-bit integer). Default value 0
*
* Example:

View file

@ -309,7 +309,7 @@ void plan_arc(
// a) is <= any configured maximum speed,
// b) does not require centripetal force greater than any configured maximum acceleration,
// c) is <= nominal speed,
// d) allows the print head to stop in the remining length of the curve within all configured maximum accelerations.
// d) allows the print head to stop in the remaining length of the curve within all configured maximum accelerations.
// The last has to be calculated every time through the loop.
const float limiting_accel = _MIN(planner.settings.max_acceleration_mm_per_s2[axis_p], planner.settings.max_acceleration_mm_per_s2[axis_q]),
limiting_speed = _MIN(planner.settings.max_feedrate_mm_s[axis_p], planner.settings.max_feedrate_mm_s[axis_q]),

View file

@ -39,7 +39,7 @@
* F<watts/kelvin> Ambient heat transfer coefficient (fan on full).
* H<joules/kelvin/mm> Filament heat capacity per mm.
* P<watts> Heater power.
* R<kelvin/second/kelvin> Sensor responsiveness (= transfer coefficient / heat capcity).
* R<kelvin/second/kelvin> Sensor responsiveness (= transfer coefficient / heat capacity).
*
* With MPC_AUTOTUNE:
* T Autotune the extruder specified with 'E' or the active extruder.
@ -65,7 +65,7 @@ void GcodeSuite::M306() {
default: tuning_type = Temperature::MPCTuningType::AUTO; break;
}
if (TERN0(MPC_PTC, tuning_type == Temperature::MPCTuningType::FORCE_ASYMPTOTIC))
SERIAL_ECHOLNPGM("Aymptotic tuning not avaiable for PTC hotends");
SERIAL_ECHOLNPGM("Asymptotic tuning not available for PTC hotends");
else {
LCD_MESSAGE(MSG_MPC_AUTOTUNE);
thermalManager.MPC_autotune(e, tuning_type);

View file

@ -37,14 +37,14 @@
#endif
typedef struct {
int32_t maxValue = 0; // Auxiliar max integer/scaled float value
int32_t minValue = 0; // Auxiliar min integer/scaled float value
int8_t dp = 0; // Auxiliar decimal places
int32_t value = 0; // Auxiliar integer / scaled float value
int16_t *intPtr = nullptr; // Auxiliar pointer to 16 bit integer variable
float *floatPtr = nullptr; // Auxiliar pointer to float variable
void (*apply)() = nullptr; // Auxiliar apply function
void (*liveUpdate)() = nullptr; // Auxiliar live update function
int32_t maxValue = 0; // Auxiliary max integer/scaled float value
int32_t minValue = 0; // Auxiliary min integer/scaled float value
int8_t dp = 0; // Auxiliary decimal places
int32_t value = 0; // Auxiliary integer / scaled float value
int16_t *intPtr = nullptr; // Auxiliary pointer to 16 bit integer variable
float *floatPtr = nullptr; // Auxiliary pointer to float variable
void (*apply)() = nullptr; // Auxiliary apply function
void (*liveUpdate)() = nullptr; // Auxiliary live update function
} MenuData_t;
extern MenuData_t menuData;

View file

@ -28,7 +28,7 @@
* (not affiliated with Anycubic, Ltd.)
*
* The AC panel wants files in block of 4 and can only display a flat list
* This library allows full folder traversal or flat file display and supports both standerd and new style panels.
* This library allows full folder traversal or flat file display and supports both standard and new style panels.
*
* ## Old Style TFT panel
* Supported chars {}[]-+=_"$%^&*()~<>|

View file

@ -496,7 +496,7 @@ namespace Anycubic {
#endif
case AC_printer_printing:
case AC_printer_paused:
// Heater timout, send acknowledgement
// Heater timeout, send acknowledgement
if (strcmp_P(msg, MARLIN_msg_heater_timeout) == 0) {
pause_state = AC_paused_heater_timed_out;
tftSendLn(AC_msg_paused); // enable continue button

View file

@ -75,7 +75,7 @@ void MoveAxisScreen::onRedraw(draw_mode_t what) {
#endif
w.increments();
#ifdef PARKING_COMMAND_GCODE
if (!ExtUI::isPrinting()) { // making sure the Tool Head Swap Position is not avalible while printing
if (!ExtUI::isPrinting()) { // making sure the Tool Head Swap Position is not available while printing
cmd.font(font_medium)
.colors(normal_btn)
.tag(25).button(BTN_POS(1,(7+EXTRUDERS)), BTN_SIZE(13,1), GET_TEXT_F(MSG_TOOL_HEAD_SWAP));

View file

@ -159,7 +159,7 @@ void xatc_wizard_goto_next_point() {
z_offset /= XATC_MAX_POINTS;
// Subtract the average from the values found with this wizard.
// This way they are indipendent from the z-offset
// This way they are independent from the z-offset
for (uint8_t i = 0; i < XATC_MAX_POINTS; ++i) xatc.z_offset[i] -= z_offset;
ui.goto_screen(xatc_wizard_update_z_offset);

View file

@ -162,7 +162,7 @@ void Canvas::addImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors)
rle_state.dsty = dsty;
rle_state.srcx = srcx;
rle_state.srcy = srcy;
rle_state.rle_offset = bytedata - (uint8_t *)images[image].data;; // Keep these for skipping full RLE decode on future iteratons
rle_state.rle_offset = bytedata - (uint8_t *)images[image].data;; // Keep these for skipping full RLE decode on future iterations
}
uint8_t count = *bytedata++; // Get the count byte

View file

@ -122,7 +122,7 @@ void TFT_String::add_glyphs(const uint8_t *font) {
}
glyph_t *TFT_String::glyph(uint16_t character) {
if (character == 0x2026) character = 0x0a; /* character 0x2026 "…" is remaped to 0x0a and should be part of symbols font */
if (character == 0x2026) character = 0x0a; /* character 0x2026 "…" is remapped to 0x0a and should be part of symbols font */
if (character < 0x00ff) return glyphs[character] ?: glyphs['?']; /* Use '?' for unknown glyphs */
#if EXTRA_GLYPHS

View file

@ -142,7 +142,7 @@ planner_settings_t Planner::settings; // Initialized by settings.load
/**
* Set up inline block variables
* Set laser_power_floor based on SPEED_POWER_MIN to pevent a zero power output state with LASER_POWER_TRAP
* Set laser_power_floor based on SPEED_POWER_MIN to prevent a zero power output state with LASER_POWER_TRAP
*/
#if ENABLED(LASER_FEATURE)
laser_state_t Planner::laser_inline; // Current state for blocks
@ -2507,7 +2507,7 @@ bool Planner::_populate_block(
* Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
* Let a circle be tangent to both previous and current path line segments, where the junction
* deviation is defined as the distance from the junction to the closest edge of the circle,
* colinear with the circle center. The circular segment joining the two paths represents the
* collinear with the circle center. The circular segment joining the two paths represents the
* path of centripetal acceleration. Solve for max velocity based on max acceleration about the
* radius of the circle, defined indirectly by junction deviation. This may be also viewed as
* path width or max_jerk in the previous Grbl version. This approach does not actually deviate
@ -3191,7 +3191,7 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) {
/**
* Set the machine positions in millimeters (soon) given the native position.
* Synchonized with the planner queue.
* Synchronized with the planner queue.
*
* - Modifiers are applied for skew, leveling, retract, etc.
* - Kinematics are applied to remap cartesian positions to stepper positions.

View file

@ -49,7 +49,7 @@ static inline float interp(const_float_t a, const_float_t b, const_float_t t) {
* Compute a Bézier curve using the De Casteljau's algorithm (see
* https://en.wikipedia.org/wiki/De_Casteljau%27s_algorithm), which is
* easy to code and has good numerical stability (very important,
* since Arudino works with limited precision real numbers).
* since Arduino works with limited precision real numbers).
*/
static inline float eval_bezier(const_float_t a, const_float_t b, const_float_t c, const_float_t d, const_float_t t) {
const float iab = interp(a, b, t),

View file

@ -2474,7 +2474,7 @@ hal_timer_t Stepper::block_phase_isr() {
* isPowered - True when a move is powered.
* isEnabled - laser power is active.
*
* Laser power variables are calulated and stored in this block by the planner code.
* Laser power variables are calculated and stored in this block by the planner code.
* trap_ramp_active_pwr - the active power in this block across accel or decel trap steps.
* trap_ramp_entry_incr - holds the precalculated value to increase the current power per accel step.
*/

View file

@ -38,7 +38,7 @@
* ...as measured on an LPC1768 with a scope and converted to cycles.
* Not applicable to other 32-bit processors, but as long as others
* take longer, pulses will be longer. For example the SKR Pro
* (stm32f407zgt6) requires ~60 cyles.
* (stm32f407zgt6) requires ~60 cycles.
*/
constexpr uint32_t timer_read_add_and_store_cycles = 34UL;

View file

@ -53,7 +53,7 @@
* Q_STEP_INIT() Q_STEP_WRITE(S) Q_STEP_READ()
*
* Steppers may not have an enable state or may be enabled by other methods
* beyond a single pin (SOFTWARE_DRIVER_ENABLE) so these can be overriden:
* beyond a single pin (SOFTWARE_DRIVER_ENABLE) so these can be overridden:
* ENABLE_STEPPER_Q() DISABLE_STEPPER_Q()
*
* Axis Stepper Control (X Y Z I J K U V W)

View file

@ -31,7 +31,7 @@
// B Value 3950K at 25/50 deg. C
// B Value Tolerance + / - 1%
constexpr temp_entry_t temptable_61[] PROGMEM = {
{ OV( 2.00), 420 }, // Guestimate to ensure we don't lose a reading and drop temps to -50 when over
{ OV( 2.00), 420 }, // Guesstimate to ensure we don't lose a reading and drop temps to -50 when over
{ OV( 12.07), 350 },
{ OV( 12.79), 345 },
{ OV( 13.59), 340 },

View file

@ -93,7 +93,7 @@
*/
//#define E0_HARDWARE_SERIAL MSerial4
// This is the stable default value after testing, but, higher UART rates could be configured, remeber to test the Steppers with the M122 command to check if everything works.
// This is the stable default value after testing, but, higher UART rates could be configured, remember to test the Steppers with the M122 command to check if everything works.
//#define TMC_BAUD_RATE 250000
#define E0_SERIAL_TX_PIN PA15

View file

@ -92,7 +92,7 @@ Once the entry and exit power values are determined, the values are divided into
trap step power incr_decr = ( cruize power - entry_exit ) / accel_decel_steps
The trap steps are incremented or decremented during each accel or decel step until the block is complete.
Step power is either cumulatively added or subtracted during trapeziod ramp progressions.
Step power is either cumulatively added or subtracted during trapezoid ramp progressions.
#### Planner Code: