Skip to content

Commit

Permalink
Merge branch 'bugfix-2.1.x' of github.com:MarlinFirmware/Marlin into …
Browse files Browse the repository at this point in the history
…leo_1S_S6_btt_mini
  • Loading branch information
JaxTheWolf committed Jul 13, 2024
2 parents d676dd6 + 95c1b7f commit b8ed0a1
Show file tree
Hide file tree
Showing 62 changed files with 927 additions and 332 deletions.
16 changes: 13 additions & 3 deletions Marlin/Configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@
* Serial port -1 is the USB emulated serial port, if available.
* Note: The first serial port (-1 or 0) will always be used by the Arduino bootloader.
*
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7]
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
*/
#define SERIAL_PORT -1

Expand All @@ -99,19 +99,29 @@
/**
* Select a secondary serial port on the board to use for communication with the host.
* Currently Ethernet (-2) is only supported on Teensy 4.1 boards.
* :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7]
* :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
*/
//#define SERIAL_PORT_2 -1
//#define BAUDRATE_2 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE

/**
* Select a third serial port on the board to use for communication with the host.
* Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7]
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
*/
//#define SERIAL_PORT_3 1
//#define BAUDRATE_3 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE

/**
* Select a serial port to communicate with RS485 protocol
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
*/
//#define RS485_SERIAL_PORT 1
#ifdef RS485_SERIAL_PORT
//#define M485_PROTOCOL 1 // Check your host for protocol compatibility
//#define RS485_BUS_BUFFER_SIZE 128
#endif

// Enable the Bluetooth serial interface on AT90USB devices
//#define BLUETOOTH

Expand Down
4 changes: 3 additions & 1 deletion Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -603,7 +603,9 @@
* (Does not work on Sanguinololu with FAN_SOFT_PWM.)
*/
#define FAN_KICKSTART_TIME 200 // (ms)
#define FAN_KICKSTART_POWER 200 // 64-255
#define FAN_KICKSTART_POWER 255 // 64-255
#define FAN_KICKSTART_LINEAR // Set kickstart time linearly based on the speed, e.g., for 20% (51) it will be FAN_KICKSTART_TIME * 0.2.
// Useful for quick speed up to low speed. Kickstart power must be set to 255.

// Some coolers may require a non-zero "off" state.
//#define FAN_OFF_PWM 1
Expand Down
2 changes: 1 addition & 1 deletion Marlin/Version.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
//#define STRING_DISTRIBUTION_DATE "2024-07-02"
//#define STRING_DISTRIBUTION_DATE "2024-07-12"

/**
* Defines a generic printer name to be output to the LCD after booting Marlin.
Expand Down
3 changes: 1 addition & 2 deletions Marlin/src/HAL/ESP32/timers.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,11 @@ typedef uint64_t hal_timer_t;
#if ENABLED(I2S_STEPPER_STREAM)
#define STEPPER_TIMER_PRESCALE 1
#define STEPPER_TIMER_RATE 250000 // 250khz, 4µs pulses of i2s word clock
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs // wrong would be 0.25
#else
#define STEPPER_TIMER_PRESCALE 40
#define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#endif
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs

#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts

Expand Down
8 changes: 8 additions & 0 deletions Marlin/src/HAL/STM32/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,14 @@
#endif
#endif

#ifdef RS485_SERIAL_PORT
#if WITHIN(RS485_SERIAL_PORT, 1, 9)
#define RS485_SERIAL MSERIAL(RS485_SERIAL_PORT)
#else
#error "RS485_SERIAL_PORT must be from 1 to 9."
#endif
#endif

/**
* TODO: review this to return 1 for pins that are not analog input
*/
Expand Down
3 changes: 3 additions & 0 deletions Marlin/src/HAL/STM32/MarlinSerial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@
#ifndef USART5
#define USART5 UART5
#endif
#ifndef USART6
#define USART6 UART6
#endif
#ifndef USART7
#define USART7 UART7
#endif
Expand Down
11 changes: 11 additions & 0 deletions Marlin/src/HAL/STM32F1/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,17 @@
#endif
#endif

#ifdef RS485_SERIAL_PORT
#if RS485_SERIAL_PORT == -1
#define RS485_SERIAL UsbSerial
#elif WITHIN(RS485_SERIAL_PORT, 1, NUM_UARTS)
#define RS485_SERIAL MSERIAL(RS485_SERIAL_PORT)
#else
#define RS485_SERIAL MSERIAL(1) // dummy port
static_assert(false, "RS485_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ".")
#endif
#endif

/**
* TODO: review this to return 1 for pins that are not analog input
*/
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/TEENSY31_32/timers.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ typedef uint32_t hal_timer_t;
#define FTM0_TIMER_PRESCALE_BITS 0b011
#define FTM1_TIMER_PRESCALE_BITS 0b010

#define FTM0_TIMER_RATE (F_BUS / (FTM0_TIMER_PRESCALE)) // 60MHz / 8 = 7500kHz
#define FTM0_TIMER_RATE (F_BUS / (FTM0_TIMER_PRESCALE)) // 60MHz / 8 = 7.5MHz
#define FTM1_TIMER_RATE (F_BUS / (FTM1_TIMER_PRESCALE)) // 60MHz / 4 = 15MHz

#define HAL_TIMER_RATE (FTM0_TIMER_RATE)
Expand Down
24 changes: 16 additions & 8 deletions Marlin/src/MarlinCore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,9 +261,13 @@
#include "tests/marlin_tests.h"
#endif

#if HAS_RS485_SERIAL
#include "feature/rs485.h"
#endif

PGMSTR(M112_KILL_STR, "M112 Shutdown");

MarlinState marlin_state = MF_INITIALIZING;
MarlinState marlin_state = MarlinState::MF_INITIALIZING;

// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop
bool wait_for_heatup = false;
Expand Down Expand Up @@ -377,8 +381,8 @@ void startOrResumeJob() {
}

inline void finishSDPrinting() {
if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued
marlin_state = MF_RUNNING; // Signal to stop trying
if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued
marlin_state = MarlinState::MF_RUNNING; // Signal to stop trying
TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine());
TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished());
}
Expand Down Expand Up @@ -773,7 +777,7 @@ void idle(const bool no_stepper_sleep/*=false*/) {
TERN_(MAX7219_DEBUG, max7219.idle_tasks());

// Return if setup() isn't completed
if (marlin_state == MF_INITIALIZING) goto IDLE_DONE;
if (marlin_state == MarlinState::MF_INITIALIZING) goto IDLE_DONE;

// TODO: Still causing errors
TERN_(TOOL_SENSOR, (void)check_tool_sensor_stats(active_extruder, true));
Expand Down Expand Up @@ -959,7 +963,7 @@ void stop() {
SERIAL_ERROR_MSG(STR_ERR_STOPPED);
LCD_MESSAGE(MSG_STOPPED);
safe_delay(350); // allow enough time for messages to get out before stopping
marlin_state = MF_STOPPED;
marlin_state = MarlinState::MF_STOPPED;
}
}

Expand Down Expand Up @@ -1273,7 +1277,7 @@ void setup() {

// Identify myself as Marlin x.x.x
SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION);
#if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR)
#ifdef STRING_DISTRIBUTION_DATE
SERIAL_ECHO_MSG(
" Last Updated: " STRING_DISTRIBUTION_DATE
" | Author: " STRING_CONFIG_H_AUTHOR
Expand Down Expand Up @@ -1642,11 +1646,15 @@ void setup() {
SETUP_RUN(bdl.init(I2C_BD_SDA_PIN, I2C_BD_SCL_PIN, I2C_BD_DELAY));
#endif

#if HAS_RS485_SERIAL
SETUP_RUN(rs485_init());
#endif

#if ENABLED(FT_MOTION)
SETUP_RUN(ftMotion.init());
#endif

marlin_state = MF_RUNNING;
marlin_state = MarlinState::MF_RUNNING;

#ifdef STARTUP_TUNE
// Play a short startup tune before continuing.
Expand Down Expand Up @@ -1678,7 +1686,7 @@ void loop() {

#if HAS_MEDIA
if (card.flag.abort_sd_printing) abortSDPrinting();
if (marlin_state == MF_SD_COMPLETE) finishSDPrinting();
if (marlin_state == MarlinState::MF_SD_COMPLETE) finishSDPrinting();
#endif

queue.advance();
Expand Down
6 changes: 3 additions & 3 deletions Marlin/src/MarlinCore.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, co
void minkill(const bool steppers_off=false);

// Global State of the firmware
enum MarlinState : uint8_t {
enum class MarlinState : uint8_t {
MF_INITIALIZING = 0,
MF_STOPPED,
MF_KILLED,
Expand All @@ -53,8 +53,8 @@ enum MarlinState : uint8_t {
};

extern MarlinState marlin_state;
inline bool IsRunning() { return marlin_state >= MF_RUNNING; }
inline bool IsStopped() { return marlin_state == MF_STOPPED; }
inline bool IsRunning() { return marlin_state >= MarlinState::MF_RUNNING; }
inline bool IsStopped() { return marlin_state == MarlinState::MF_STOPPED; }

bool printingIsActive();
bool printJobOngoing();
Expand Down
9 changes: 5 additions & 4 deletions Marlin/src/feature/backlash.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,13 +171,14 @@ int32_t Backlash::get_applied_steps(const AxisEnum axis) {

const int32_t residual_error_axis = residual_error[axis];

// At startup it is assumed the last move was forward.
// So the applied steps will always be negative.
// At startup, when no steps are applied, it is assumed the last move was backwards.
// So the applied steps will always be zero (when moving backwards) or a positive
// number (when moving forwards).

if (forward) return -residual_error_axis;
if (!forward) return -residual_error_axis;

const float f_corr = float(correction) / all_on;
const int32_t full_error_axis = -f_corr * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis];
const int32_t full_error_axis = f_corr * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis];
return full_error_axis - residual_error_axis;
}

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/feature/ethernet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ void MarlinEthernet::check() {

case CONNECTING:
telnetClient.println("Marlin " SHORT_BUILD_VERSION);
#if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR)
#ifdef STRING_DISTRIBUTION_DATE
telnetClient.println(
" Last Updated: " STRING_DISTRIBUTION_DATE
" | Author: " STRING_CONFIG_H_AUTHOR
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/feature/leds/leds.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ void LEDLights::set_color(const LEDColor &incol
void LEDLights::toggle() { if (lights_on) set_off(); else update(); }
#endif

#if LED_POWEROFF_TIMEOUT > 0
#if HAS_LED_POWEROFF_TIMEOUT

millis_t LEDLights::led_off_time; // = 0

Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/feature/leds/leds.h
Original file line number Diff line number Diff line change
Expand Up @@ -164,11 +164,11 @@ class LEDLights {
#if ENABLED(LED_CONTROL_MENU)
static void toggle(); // swap "off" with color
#endif
#if ANY(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) || LED_POWEROFF_TIMEOUT > 0
#if ANY(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED, HAS_LED_POWEROFF_TIMEOUT)
static void update() { set_color(color); }
#endif

#if LED_POWEROFF_TIMEOUT > 0
#if HAS_LED_POWEROFF_TIMEOUT
private:
static millis_t led_off_time;
public:
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/feature/power.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ void Power::power_off() {
/**
* Check all conditions that would signal power needing to be on.
*
* @returns bool if power is needed
* @return bool if power is needed
*/
bool Power::is_power_needed() {

Expand Down
39 changes: 39 additions & 0 deletions Marlin/src/feature/rs485.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2024 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 "../inc/MarlinConfig.h"

#if HAS_RS485_SERIAL

#include "rs485.h"

HardwareSerialBusIO rs485BusIO(&RS485_SERIAL);
RS485Bus<RS485_BUS_BUFFER_SIZE> rs485Bus(rs485BusIO, RS485_RX_ENABLE_PIN, RS485_TX_ENABLE_PIN);

PhotonProtocol rs485Protocol;

Packetizer rs485Packetizer(rs485Bus, rs485Protocol);

uint8_t rs485Buffer[RS485_SEND_BUFFER_SIZE];

void rs485_init() { RS485_SERIAL.begin(57600); }

#endif // HAS_RS485_SERIAL
40 changes: 40 additions & 0 deletions Marlin/src/feature/rs485.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2024 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"

#include <rs485/rs485bus.hpp>
#include <rs485/bus_adapters/hardware_serial.h>

#include <rs485/protocols/photon.h>
#include <rs485/packetizer.h>

#define RS485_SEND_BUFFER_SIZE 32

extern HardwareSerialBusIO rs485BusIO;
extern RS485Bus<RS485_BUS_BUFFER_SIZE> rs485Bus;
extern PhotonProtocol rs485Protocol;
extern Packetizer rs485Packetizer;
extern uint8_t rs485Buffer[RS485_SEND_BUFFER_SIZE];

void rs485_init();
2 changes: 1 addition & 1 deletion Marlin/src/gcode/calibrate/G33.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -634,7 +634,7 @@ void GcodeSuite::G33() {
}
SERIAL_EOL();

MString<20> msg(F("Calibration sd:"));
MString<21> msg(F("Calibration sd:"));
if (zero_std_dev_min < 1)
msg.appendf(F("0.%03i"), (int)LROUND(zero_std_dev_min * 1000.0f));
else
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/gcode/control/M999.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
* existing command buffer.
*/
void GcodeSuite::M999() {
marlin_state = MF_RUNNING;
marlin_state = MarlinState::MF_RUNNING;
ui.reset_alert_level();

if (parser.boolval('S')) return;
Expand Down
Loading

0 comments on commit b8ed0a1

Please sign in to comment.