⚗️ Temperature Model Predictive Control (#23751)

This commit is contained in:
tombrazier 2022-04-01 08:14:14 +01:00 committed by Scott Lahteine
parent 3443a9e18b
commit 21c838cb1b
13 changed files with 566 additions and 32 deletions

View File

@ -589,10 +589,12 @@
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
// PID Tuning Guide here: https://reprap.org/wiki/PID_Tuning
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
// Enable PIDTEMP for PID control or MPCTEMP for Predictive Model.
// temperature control. Disable both for bang-bang heating.
#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning
//#define MPCTEMP // ** EXPERIMENTAL **
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within any PID loop
@ -612,7 +614,45 @@
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114.00
#endif
#endif // PIDTEMP
#endif
/**
* Model Predictive Control for hotend
*
* Use a physical model of the hotend to control temperature. When configured correctly
* this gives better responsiveness and stability than PID and it also removes the need
* for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 to autotune the model.
*/
#if ENABLED(MPCTEMP)
#define MPC_MAX BANG_MAX // (0..255) Current to nozzle while MPC is active.
#define MPC_HEATER_POWER { 40.0f } // (W) Heat cartridge powers.
#define MPC_INCLUDE_FAN // Model the fan speed?
// Measured physical constants from M306
#define MPC_BLOCK_HEAT_CAPACITY { 16.7f } // (J/K) Heat block heat capacities.
#define MPC_SENSOR_RESPONSIVENESS { 0.22f } // (K/s per ∆K) Rate of change of sensor temperature from heat block.
#define MPC_AMBIENT_XFER_COEFF { 0.068f } // (W/K) Heat transfer coefficients from heat block to room air with fan off.
#if ENABLED(MPC_INCLUDE_FAN)
#define MPC_AMBIENT_XFER_COEFF_FAN255 { 0.097f } // (W/K) Heat transfer coefficients from heat block to room air with fan on full.
#endif
// For one fan and multiple hotends MPC needs to know how to apply the fan cooling effect.
#if ENABLED(MPC_INCLUDE_FAN)
//#define MPC_FAN_0_ALL_HOTENDS
//#define MPC_FAN_0_ACTIVE_HOTEND
#endif
#define FILAMENT_HEAT_CAPACITY_PERMM 5.6e-3f // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA).
//#define FILAMENT_HEAT_CAPACITY_PERMM 3.6e-3f // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG).
// Advanced options
#define MPC_SMOOTHING_FACTOR 0.5f // (0.0...1.0) Noisy temperature sensors may need a lower value for stabilization.
#define MPC_MIN_AMBIENT_CHANGE 1.0f // (K/s) Modeled ambient temperature rate of change, when correcting model inaccuracies.
#define MPC_STEADYSTATE 0.5f // (K/s) Temperature change rate for steady state logic to be enforced.
#define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center just above the surface.
#endif
//===========================================================================
//====================== PID > Bed Temperature Control ======================

View File

@ -209,19 +209,19 @@ void MarlinHAL::adc_init() {
adc1_config_width(ADC_WIDTH_12Bit);
// Configure channels only if used as (re-)configuring a pin for ADC that is used elsewhere might have adverse effects
TERN_(HAS_TEMP_ADC_0, adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_1, adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_2, adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_3, adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_4, adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db));
TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_PROBE, adc1_set_attenuation(get_channel(TEMP_PROBE_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_BOARD, adc1_set_attenuation(get_channel(TEMP_BOARD_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_0, adc1_set_attenuation(get_channel(TEMP_0_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_1, adc1_set_attenuation(get_channel(TEMP_1_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_2, adc1_set_attenuation(get_channel(TEMP_2_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_3, adc1_set_attenuation(get_channel(TEMP_3_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_4, adc1_set_attenuation(get_channel(TEMP_4_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_5, adc1_set_attenuation(get_channel(TEMP_5_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_6, adc2_set_attenuation(get_channel(TEMP_6_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_ADC_7, adc3_set_attenuation(get_channel(TEMP_7_PIN), ADC_ATTEN_11db));
TERN_(HAS_HEATED_BED, adc1_set_attenuation(get_channel(TEMP_BED_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_CHAMBER, adc1_set_attenuation(get_channel(TEMP_CHAMBER_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_PROBE, adc1_set_attenuation(get_channel(TEMP_PROBE_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_COOLER, adc1_set_attenuation(get_channel(TEMP_COOLER_PIN), ADC_ATTEN_11db));
TERN_(HAS_TEMP_BOARD, adc1_set_attenuation(get_channel(TEMP_BOARD_PIN), ADC_ATTEN_11db));
TERN_(FILAMENT_WIDTH_SENSOR, adc1_set_attenuation(get_channel(FILWIDTH_PIN), ADC_ATTEN_11db));
// Note that adc2 is shared with the WiFi module, which has higher priority, so the conversion may fail.

View File

@ -787,6 +787,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 305: M305(); break; // M305: Set user thermistor parameters
#endif
#if ENABLED(MPCTEMP)
case 306: M306(); break; // M306: MPC autotune
#endif
#if ENABLED(REPETIER_GCODE_M360)
case 360: M360(); break; // M360: Firmware settings
#endif

View File

@ -215,6 +215,7 @@
* M303 - PID relay autotune S<temperature> sets the target temperature. Default 150C. (Requires PIDTEMP)
* M304 - Set bed PID parameters P I and D. (Requires PIDTEMPBED)
* M305 - Set user thermistor parameters R T and P. (Requires TEMP_SENSOR_x 1000)
* M306 - MPC autotune. (Requires MPCTEMP)
* M309 - Set chamber PID parameters P I and D. (Requires PIDTEMPCHAMBER)
* M350 - Set microstepping mode. (Requires digital microstepping pins.)
* M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.)
@ -928,6 +929,11 @@ private:
static void M305();
#endif
#if ENABLED(MPCTEMP)
static void M306();
static void M306_report(const bool forReplay=true);
#endif
#if ENABLED(PIDTEMPCHAMBER)
static void M309();
static void M309_report(const bool forReplay=true);

View File

@ -0,0 +1,86 @@
/**
* 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/>.
*
*/
#include "../../inc/MarlinConfig.h"
#if ENABLED(MPCTEMP)
#include "../gcode.h"
#include "../../module/temperature.h"
/**
* M306: MPC settings and autotune
*
* T Autotune the active extruder.
*
* A<watts/kelvin> Ambient heat transfer coefficient (no fan).
* C<joules/kelvin> Block heat capacity.
* E<extruder> Extruder number to set. (Default: E0)
* F<watts/kelvin> Ambient heat transfer coefficient (fan on full).
* P<watts> Heater power.
* R<kelvin/second/kelvin> Sensor responsiveness (= transfer coefficient / heat capcity).
*/
void GcodeSuite::M306() {
if (parser.seen_test('T')) { thermalManager.MPC_autotune(); return; }
if (parser.seen("ACFPR")) {
const heater_id_t hid = (heater_id_t)parser.intval('E', 0);
MPC_t &constants = thermalManager.temp_hotend[hid].constants;
if (parser.seenval('P')) constants.heater_power = parser.value_float();
if (parser.seenval('C')) constants.block_heat_capacity = parser.value_float();
if (parser.seenval('R')) constants.sensor_responsiveness = parser.value_float();
if (parser.seenval('A')) constants.ambient_xfer_coeff_fan0 = parser.value_float();
#if ENABLED(MPC_INCLUDE_FAN)
if (parser.seenval('F')) constants.fan255_adjustment = parser.value_float() - constants.ambient_xfer_coeff_fan0;
#endif
return;
}
HOTEND_LOOP() {
SERIAL_ECHOLNPGM("MPC constants for hotend ", e);
MPC_t& constants = thermalManager.temp_hotend[e].constants;
SERIAL_ECHOLNPGM("Heater power: ", constants.heater_power);
SERIAL_ECHOLNPGM("Heatblock heat capacity: ", constants.block_heat_capacity);
SERIAL_ECHOLNPAIR_F("Sensor responsivness: ", constants.sensor_responsiveness, 4);
SERIAL_ECHOLNPAIR_F("Ambient heat transfer coeff. (no fan): ", constants.ambient_xfer_coeff_fan0, 4);
#if ENABLED(MPC_INCLUDE_FAN)
SERIAL_ECHOLNPAIR_F("Ambient heat transfer coeff. (full fan): ", constants.ambient_xfer_coeff_fan0 + constants.fan255_adjustment, 4);
#endif
}
}
void GcodeSuite::M306_report(const bool forReplay/*=true*/) {
report_heading(forReplay, F("Model predictive control"));
HOTEND_LOOP() {
report_echo_start(forReplay);
MPC_t& constants = thermalManager.temp_hotend[e].constants;
SERIAL_ECHOPGM(" M306 E", e);
SERIAL_ECHOPAIR_F(" P", constants.heater_power, 2);
SERIAL_ECHOPAIR_F(" C", constants.block_heat_capacity, 2);
SERIAL_ECHOPAIR_F(" R", constants.sensor_responsiveness, 4);
SERIAL_ECHOPAIR_F(" A", constants.ambient_xfer_coeff_fan0, 4);
SERIAL_ECHOLNPAIR_F(" F", constants.ambient_xfer_coeff_fan0 + constants.fan255_adjustment, 4);
}
}
#endif // MPCTEMP

View File

@ -1401,6 +1401,26 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "You must set DISPLAY_CHARSET_HD44780 to JAPANESE, WESTERN or CYRILLIC for your LCD controller."
#endif
/**
* Extruder temperature control algorithm - There can be only one!
*/
#if BOTH(PIDTEMP, MPCTEMP)
#error "Only enable PIDTEMP or MPCTEMP, but not both."
#endif
#if ENABLED(MPC_INCLUDE_FAN)
#if FAN_COUNT < 1
#error "MPC_INCLUDE_FAN requires at least one fan."
#endif
#if FAN_COUNT < HOTENDS
#if COUNT_ENABLED(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) > 1
#error "Enable either MPC_FAN_0_ALL_HOTENDS or MPC_FAN_0_ACTIVE_HOTEND, not both."
#elif NONE(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND)
#error "MPC_INCLUDE_FAN requires MPC_FAN_0_ALL_HOTENDS or MPC_FAN_0_ACTIVE_HOTEND for one fan with multiple hotends."
#endif
#endif
#endif
/**
* Bed Heating Options - PID vs Limit Switching
*/

View File

@ -85,7 +85,7 @@ void ChironTFT::Startup() {
// opt_enable FIL_RUNOUT_PULLUP
TFTSer.begin(115200);
// wait for the TFT panel to initialise and finish the animation
// Wait for the TFT panel to initialize and finish the animation
safe_delay(1000);
// There are different panels for the Chiron with slightly different commands

View File

@ -85,7 +85,7 @@ void AnycubicTFTClass::OnSetup() {
SENDLINE_DBG_PGM("J17", "TFT Serial Debug: Main board reset... J17"); // J17 Main board reset
delay_ms(10);
// initialise the state of the key pins running on the tft
// Init the state of the key pins running on the TFT
#if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT)
SET_INPUT_PULLUP(SD_DETECT_PIN);
#endif

View File

@ -555,6 +555,13 @@ typedef struct SettingsDataStruct {
uint8_t ui_language; // M414 S
#endif
//
// Model predictive control
//
#if ENABLED(MPCTEMP)
MPC_t mpc_constants[HOTENDS]; // M306
#endif
} SettingsData;
//static_assert(sizeof(SettingsData) <= MARLIN_EEPROM_SIZE, "EEPROM too small to contain SettingsData!");
@ -1564,6 +1571,14 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(ui.language);
#endif
//
// Model predictive control
//
#if ENABLED(MPCTEMP)
HOTEND_LOOP()
EEPROM_WRITE(thermalManager.temp_hotend[e].constants);
#endif
//
// Report final CRC and Data Size
//
@ -2514,6 +2529,16 @@ void MarlinSettings::postprocess() {
}
#endif
//
// Model predictive control
//
#if ENABLED(MPCTEMP)
{
HOTEND_LOOP()
EEPROM_READ(thermalManager.temp_hotend[e].constants);
}
#endif
//
// Validate Final Size and CRC
//
@ -3220,6 +3245,37 @@ void MarlinSettings::reset() {
//
TERN_(DWIN_LCD_PROUI, DWIN_SetDataDefaults());
//
// Model predictive control
//
#if ENABLED(MPCTEMP)
constexpr float _mpc_heater_power[] = MPC_HEATER_POWER;
constexpr float _mpc_block_heat_capacity[] = MPC_BLOCK_HEAT_CAPACITY;
constexpr float _mpc_sensor_responsiveness[] = MPC_SENSOR_RESPONSIVENESS;
constexpr float _mpc_ambient_xfer_coeff[] = MPC_AMBIENT_XFER_COEFF;
#if ENABLED(MPC_INCLUDE_FAN)
constexpr float _mpc_ambient_xfer_coeff_fan255[] = MPC_AMBIENT_XFER_COEFF_FAN255;
#endif
static_assert(COUNT(_mpc_heater_power) == HOTENDS, "MPC_HEATER_POWER must have HOTENDS items.");
static_assert(COUNT(_mpc_block_heat_capacity) == HOTENDS, "MPC_BLOCK_HEAT_CAPACITY must have HOTENDS items.");
static_assert(COUNT(_mpc_sensor_responsiveness) == HOTENDS, "MPC_SENSOR_RESPONSIVENESS must have HOTENDS items.");
static_assert(COUNT(_mpc_ambient_xfer_coeff) == HOTENDS, "MPC_AMBIENT_XFER_COEFF must have HOTENDS items.");
#if ENABLED(MPC_INCLUDE_FAN)
static_assert(COUNT(_mpc_ambient_xfer_coeff_fan255) == HOTENDS, "MPC_AMBIENT_XFER_COEFF_FAN255 must have HOTENDS items.");
#endif
HOTEND_LOOP() {
thermalManager.temp_hotend[e].constants.heater_power = _mpc_heater_power[e];
thermalManager.temp_hotend[e].constants.block_heat_capacity = _mpc_block_heat_capacity[e];
thermalManager.temp_hotend[e].constants.sensor_responsiveness = _mpc_sensor_responsiveness[e];
thermalManager.temp_hotend[e].constants.ambient_xfer_coeff_fan0 = _mpc_ambient_xfer_coeff[e];
#if ENABLED(MPC_INCLUDE_FAN)
thermalManager.temp_hotend[e].constants.fan255_adjustment = _mpc_ambient_xfer_coeff_fan255[e] - _mpc_ambient_xfer_coeff[e];
#endif
}
#endif
postprocess();
#if EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE)
@ -3506,6 +3562,11 @@ void MarlinSettings::reset() {
#endif
TERN_(HAS_MULTI_LANGUAGE, gcode.M414_report(forReplay));
//
// Model predictive control
//
TERN_(MPCTEMP, gcode.M306_report(forReplay));
}
#endif // !DISABLE_M503

View File

@ -141,7 +141,8 @@
#endif
#endif
#if ENABLED(PID_EXTRUSION_SCALING)
#if EITHER(MPCTEMP, PID_EXTRUSION_SCALING)
#include <math.h>
#include "stepper.h"
#endif
@ -509,10 +510,14 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED);
volatile bool Temperature::raw_temps_ready = false;
#if ENABLED(PID_EXTRUSION_SCALING)
int32_t Temperature::last_e_position, Temperature::lpq[LPQ_MAX_LEN];
int32_t Temperature::pes_e_position, Temperature::lpq[LPQ_MAX_LEN];
lpq_ptr_t Temperature::lpq_ptr = 0;
#endif
#if ENABLED(MPCTEMP)
int32_t Temperature::mpc_e_position; // = 0
#endif
#define TEMPDIR(N) ((TEMP_SENSOR_##N##_RAW_LO_TEMP) < (TEMP_SENSOR_##N##_RAW_HI_TEMP) ? 1 : -1)
#define TP_CMP(S,A,B) (TEMPDIR(S) < 0 ? ((A)<(B)) : ((A)>(B)))
@ -587,8 +592,8 @@ volatile bool Temperature::raw_temps_ready = false;
PID_t tune_pid = { 0, 0, 0 };
celsius_float_t maxT = 0, minT = 10000;
const bool isbed = (heater_id == H_BED);
const bool ischamber = (heater_id == H_CHAMBER);
const bool isbed = (heater_id == H_BED),
ischamber = (heater_id == H_CHAMBER);
#if ENABLED(PIDTEMPCHAMBER)
#define C_TERN(T,A,B) ((T) ? (A) : (B))
@ -846,6 +851,198 @@ volatile bool Temperature::raw_temps_ready = false;
#endif // HAS_PID_HEATING
#if ENABLED(MPCTEMP)
void Temperature::MPC_autotune() {
auto housekeeping = [] (millis_t& ms, celsius_float_t& current_temp, millis_t& next_report_ms) {
ms = millis();
if (updateTemperaturesIfReady()) { // temp sample ready
current_temp = degHotend(active_extruder);
TERN_(HAS_FAN_LOGIC, manage_extruder_fans(ms));
}
if (ELAPSED(ms, next_report_ms)) {
next_report_ms += 1000UL;
SERIAL_ECHOLNPGM("Temperature ", current_temp);
}
hal.idletask();
};
SERIAL_ECHOLNPGM("Measuring MPC constants for E", active_extruder);
MPCHeaterInfo& hotend = temp_hotend[active_extruder];
MPC_t& constants = hotend.constants;
// move to center of bed, just above bed height and cool with max fan
SERIAL_ECHOLNPGM("Moving to tuning position");
TERN_(HAS_FAN, zero_fan_speeds());
disable_all_heaters();
TERN_(HAS_FAN, set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255));
TERN_(HAS_FAN, planner.sync_fan_speeds(fan_speed));
gcode.home_all_axes(true);
const xyz_pos_t tuningpos = MPC_TUNING_POS;
do_blocking_move_to(tuningpos);
SERIAL_ECHOLNPGM("Cooling to ambient");
millis_t ms = millis(), next_report_ms = ms, next_test_ms = ms + 10000UL;
celsius_float_t current_temp = degHotend(active_extruder),
ambient_temp = current_temp;
wait_for_heatup = true; // Can be interrupted with M108
while (wait_for_heatup) {
housekeeping(ms, current_temp, next_report_ms);
if (ELAPSED(ms, next_test_ms)) {
if (current_temp >= ambient_temp) {
ambient_temp = (ambient_temp + current_temp) / 2.0f;
break;
}
ambient_temp = current_temp;
next_test_ms += 10000UL;
}
}
TERN_(HAS_FAN, set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 0));
TERN_(HAS_FAN, planner.sync_fan_speeds(fan_speed));
hotend.modeled_ambient_temp = ambient_temp;
SERIAL_ECHOLNPGM("Heating to 200C");
hotend.soft_pwm_amount = MPC_MAX >> 1;
const millis_t heat_start_time = ms;
next_test_ms = ms;
celsius_float_t temp_samples[16];
uint8_t sample_count = 0;
uint16_t sample_distance = 1;
float t1_time = 0;
while (wait_for_heatup) {
housekeeping(ms, current_temp, next_report_ms);
if (ELAPSED(ms, next_test_ms)) {
// record samples between 100C and 200C
if (current_temp >= 100.0f) {
// if there are too many samples, space them more widely
if (sample_count == COUNT(temp_samples)) {
for (uint8_t i = 0; i < COUNT(temp_samples) / 2; i++)
temp_samples[i] = temp_samples[i*2];
sample_count /= 2;
sample_distance *= 2;
}
if (sample_count == 0) t1_time = float(ms - heat_start_time) / 1000.0f;
temp_samples[sample_count++] = current_temp;
}
if (current_temp >= 200.0f) break;
next_test_ms += 1000UL * sample_distance;
}
}
hotend.soft_pwm_amount = 0;
// calculate physical constants from three equally spaced samples
sample_count = (sample_count + 1) / 2 * 2 - 1;
const float t1 = temp_samples[0],
t2 = temp_samples[(sample_count - 1) >> 1],
t3 = temp_samples[sample_count - 1],
asymp_temp = (t2 * t2 - t1 * t3) / (2 * t2 - t1 - t3),
block_responsiveness = -log((t2 - asymp_temp) / (t1 - asymp_temp)) / (sample_distance * (sample_count >> 1));
constants.ambient_xfer_coeff_fan0 = constants.heater_power * MPC_MAX / 255 / (asymp_temp - ambient_temp);
constants.fan255_adjustment = 0.0f;
constants.block_heat_capacity = constants.ambient_xfer_coeff_fan0 / block_responsiveness;
constants.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp));
hotend.modeled_block_temp = asymp_temp + (ambient_temp - asymp_temp) * exp(-block_responsiveness * (ms - heat_start_time) / 1000.0f);
hotend.modeled_sensor_temp = current_temp;
// let the system stabilise under MPC control then get a better measure of ambient loss without and with fan
SERIAL_ECHOLNPGM("Measuring ambient heatloss at target ", hotend.modeled_block_temp);
hotend.target = hotend.modeled_block_temp;
next_test_ms = ms + MPC_dT * 1000;
constexpr millis_t settle_time = 20000UL,
test_length = 20000UL;
millis_t settle_end_ms = ms + settle_time,
test_end_ms = settle_end_ms + test_length;
float total_energy_fan0 = 0.0f;
#if HAS_FAN
bool fan0_done = false;
float total_energy_fan255 = 0.0f;
#endif
float last_temp = current_temp;
while (wait_for_heatup) {
housekeeping(ms, current_temp, next_report_ms);
if (ELAPSED(ms, next_test_ms)) {
// use MPC to control the temperature, let it settle for 30s and then track power output for 10s
hotend.soft_pwm_amount = (int)get_pid_output_hotend(active_extruder) >> 1;
if (ELAPSED(ms, settle_end_ms) && !ELAPSED(ms, test_end_ms) && TERN1(HAS_FAN, !fan0_done))
total_energy_fan0 += constants.heater_power * hotend.soft_pwm_amount / 127 * MPC_dT + (last_temp - current_temp) * constants.block_heat_capacity;
#if HAS_FAN
else if (ELAPSED(ms, test_end_ms) && !fan0_done) {
SERIAL_ECHOLNPGM("Measuring ambient heatloss with full fan");
set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255);
planner.sync_fan_speeds(fan_speed);
settle_end_ms = ms + settle_time;
test_end_ms = settle_end_ms + test_length;
fan0_done = true;
}
else if (ELAPSED(ms, settle_end_ms) && !ELAPSED(ms, test_end_ms))
total_energy_fan255 += constants.heater_power * hotend.soft_pwm_amount / 127 * MPC_dT + (last_temp - current_temp) * constants.block_heat_capacity;
#endif
else if (ELAPSED(ms, test_end_ms)) break;
last_temp = current_temp;
next_test_ms += MPC_dT * 1000;
}
if (!WITHIN(current_temp, hotend.target - 15.0f, hotend.target + 15.0f)) {
SERIAL_ECHOLNPGM("Temperature error while measuring ambient loss");
break;
}
}
const float power_fan0 = total_energy_fan0 * 1000 / test_length;
constants.ambient_xfer_coeff_fan0 = power_fan0 / (hotend.target - ambient_temp);
#if HAS_FAN
const float power_fan255 = total_energy_fan255 * 1000 / test_length,
ambient_xfer_coeff_fan255 = power_fan255 / (hotend.target - ambient_temp);
constants.fan255_adjustment = ambient_xfer_coeff_fan255 - constants.ambient_xfer_coeff_fan0;
#endif
hotend.target = 0.0f;
hotend.soft_pwm_amount = 0;
TERN_(HAS_FAN, set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 0));
TERN_(HAS_FAN, planner.sync_fan_speeds(fan_speed));
if (!wait_for_heatup) SERIAL_ECHOLNPGM("Test was interrupted");
wait_for_heatup = false;
SERIAL_ECHOLNPGM("Done");
/* <-- add a slash to enable
SERIAL_ECHOLNPGM("t1_time ", t1_time);
SERIAL_ECHOLNPGM("sample_count ", sample_count);
SERIAL_ECHOLNPGM("sample_distance ", sample_distance);
for (uint8_t i = 0; i < sample_count; i++)
SERIAL_ECHOLNPGM("sample ", i, " : ", temp_samples[i]);
SERIAL_ECHOLNPGM("t1 ", t1, " t2 ", t2, " t3 ", t3);
SERIAL_ECHOLNPGM("asymp_temp ", asymp_temp);
SERIAL_ECHOLNPAIR_F("block_responsiveness ", block_responsiveness, 4);
//*/
SERIAL_ECHOLNPGM("MPC_BLOCK_HEAT_CAPACITY ", constants.block_heat_capacity);
SERIAL_ECHOLNPAIR_F("MPC_SENSOR_RESPONSIVENESS ", constants.sensor_responsiveness, 4);
SERIAL_ECHOLNPAIR_F("MPC_AMBIENT_XFER_COEFF ", constants.ambient_xfer_coeff_fan0, 4);
TERN_(HAS_FAN, SERIAL_ECHOLNPAIR_F("MPC_AMBIENT_XFER_COEFF_FAN255 ", ambient_xfer_coeff_fan255, 4));
}
#endif // MPCTEMP
int16_t Temperature::getHeaterPower(const heater_id_t heater_id) {
switch (heater_id) {
#if HAS_HEATED_BED
@ -1101,7 +1298,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) {
pid_reset.set(ee);
}
else if (pid_error > PID_FUNCTIONAL_RANGE) {
pid_output = BANG_MAX;
pid_output = PID_MAX;
pid_reset.set(ee);
}
else {
@ -1128,9 +1325,9 @@ void Temperature::min_temp_error(const heater_id_t heater_id) {
work_pid[ee].Kc = 0;
if (this_hotend) {
const long e_position = stepper.position(E_AXIS);
if (e_position > last_e_position) {
lpq[lpq_ptr] = e_position - last_e_position;
last_e_position = e_position;
if (e_position > pes_e_position) {
lpq[lpq_ptr] = e_position - pes_e_position;
pes_e_position = e_position;
}
else
lpq[lpq_ptr] = 0;
@ -1173,7 +1370,86 @@ void Temperature::min_temp_error(const heater_id_t heater_id) {
}
#endif
#else // No PID enabled
#elif ENABLED(MPCTEMP)
MPCHeaterInfo& hotend = temp_hotend[ee];
MPC_t& constants = hotend.constants;
// At startup, initialize modeled temperatures
if (isnan(hotend.modeled_block_temp)) {
hotend.modeled_ambient_temp = min(30.0f, hotend.celsius); // cap initial value at reasonable max room temperature of 30C
hotend.modeled_block_temp = hotend.modeled_sensor_temp = hotend.celsius;
}
#if HOTENDS == 1
constexpr bool this_hotend = true;
#else
const bool this_hotend = (ee == active_extruder);
#endif
float ambient_xfer_coeff = constants.ambient_xfer_coeff_fan0;
#if ENABLED(MPC_INCLUDE_FAN)
const uint8_t fan_index = ANY(MPC_FAN_0_ACTIVE_HOTEND, MPC_FAN_0_ALL_HOTENDS) ? 0 : ee;
const float fan_fraction = TERN_(MPC_FAN_0_ACTIVE_HOTEND, !this_hotend ? 0.0f : ) fan_speed[fan_index] * RECIPROCAL(255);
ambient_xfer_coeff += fan_fraction * constants.fan255_adjustment;
#endif
if (this_hotend) {
const int32_t e_position = stepper.position(E_AXIS);
const float e_speed = (e_position - mpc_e_position) * planner.mm_per_step[E_AXIS] / MPC_dT;
// the position can appear to make big jumps when, e.g. homing
if (fabs(e_speed) > planner.settings.max_feedrate_mm_s[E_AXIS])
mpc_e_position = e_position;
else if (e_speed > 0.0f) { // ignore retract/recover moves
ambient_xfer_coeff += e_speed * FILAMENT_HEAT_CAPACITY_PERMM;
mpc_e_position = e_position;
}
}
// update the modeled temperatures
float blocktempdelta = hotend.soft_pwm_amount * constants.heater_power * (MPC_dT / 127) / constants.block_heat_capacity;
blocktempdelta += (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff * MPC_dT / constants.block_heat_capacity;
hotend.modeled_block_temp += blocktempdelta;
const float sensortempdelta = (hotend.modeled_block_temp - hotend.modeled_sensor_temp) * (constants.sensor_responsiveness * MPC_dT);
hotend.modeled_sensor_temp += sensortempdelta;
// Any delta between hotend.modeled_sensor_temp and hotend.celsius is either model
// error diverging slowly or (fast) noise. Slowly correct towards this temperature and noise will average out.
const float delta_to_apply = (hotend.celsius - hotend.modeled_sensor_temp) * (MPC_SMOOTHING_FACTOR);
hotend.modeled_block_temp += delta_to_apply;
hotend.modeled_sensor_temp += delta_to_apply;
// only correct ambient when close to steady state (output power is not clipped or asymptotic temperature is reached)
if (WITHIN(hotend.soft_pwm_amount, 1, 126) || fabs(blocktempdelta + delta_to_apply) < (MPC_STEADYSTATE * MPC_dT))
hotend.modeled_ambient_temp += delta_to_apply > 0.f ? max(delta_to_apply, MPC_MIN_AMBIENT_CHANGE * MPC_dT) : min(delta_to_apply, -MPC_MIN_AMBIENT_CHANGE * MPC_dT);
float power = 0.0;
if (hotend.target != 0 && TERN1(HEATER_IDLE_HANDLER, !heater_idle[ee].timed_out)) {
// plan power level to get to target temperature in 2 seconds
power = (hotend.target - hotend.modeled_block_temp) * constants.block_heat_capacity / 2.0f;
power -= (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff;
}
float pid_output = power * 254.0f / constants.heater_power + 1.0f; // ensure correct quantization into a range of 0 to 127
pid_output = constrain(pid_output, 0, MPC_MAX);
/* <-- add a slash to enable
static uint32_t nexttime = millis() + 1000;
if (ELAPSED(millis(), nexttime)) {
nexttime += 1000;
SERIAL_ECHOLNPGM("block temp ", hotend.modeled_block_temp,
", celsius ", hotend.celsius,
", blocktempdelta ", blocktempdelta,
", delta_to_apply ", delta_to_apply,
", ambient ", hotend.modeled_ambient_temp,
", power ", power,
", pid_output ", pid_output,
", pwm ", (int)pid_output >> 1);
}
//*/
#else // No PID or MPC enabled
const bool is_idling = TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out);
const float pid_output = (!is_idling && temp_hotend[ee].celsius < temp_hotend[ee].target) ? BANG_MAX : 0;
@ -2178,7 +2454,7 @@ void Temperature::init() {
TERN_(PROBING_HEATERS_OFF, paused_for_probing = false);
#if BOTH(PIDTEMP, PID_EXTRUSION_SCALING)
last_e_position = 0;
pes_e_position = 0;
#endif
// Init (and disable) SPI thermocouples
@ -2248,6 +2524,10 @@ void Temperature::init() {
));
#endif
#if ENABLED(MPCTEMP)
HOTEND_LOOP() temp_hotend[e].modeled_block_temp = NAN;
#endif
#if HAS_HEATER_0
#ifdef BOARD_OPENDRAIN_MOSFETS
OUT_WRITE_OD(HEATER_0_PIN, HEATER_0_INVERTING);

View File

@ -94,6 +94,18 @@ hotend_pid_t;
#define _PID_Kf(H) 0
#endif
#if ENABLED(MPCTEMP)
typedef struct {
float heater_power; // M306 P
float block_heat_capacity; // M306 C
float sensor_responsiveness; // M306 R
float ambient_xfer_coeff_fan0; // M306 A
#if ENABLED(MPC_INCLUDE_FAN)
float fan255_adjustment; // M306 F
#endif
} MPC_t;
#endif
/**
* States for ADC reading in the ISR
*/
@ -177,7 +189,7 @@ enum ADCSensorState : char {
#if HAS_PID_HEATING
#define PID_K2 (1-float(PID_K1))
#define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / TEMP_TIMER_FREQUENCY)
#define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / (TEMP_TIMER_FREQUENCY))
// Apply the scale factors to the PID values
#define scalePID_i(i) ( float(i) * PID_dT )
@ -186,6 +198,10 @@ enum ADCSensorState : char {
#define unscalePID_d(d) ( float(d) * PID_dT )
#endif
#if ENABLED(MPCTEMP)
#define MPC_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / (TEMP_TIMER_FREQUENCY))
#endif
#if ENABLED(G26_MESH_VALIDATION) && EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI)
#define G26_CLICK_CAN_CANCEL 1
#endif
@ -223,8 +239,19 @@ struct PIDHeaterInfo : public HeaterInfo {
T pid; // Initialized by settings.load()
};
#if ENABLED(MPCTEMP)
struct MPCHeaterInfo : public HeaterInfo {
MPC_t constants;
float modeled_ambient_temp,
modeled_block_temp,
modeled_sensor_temp;
};
#endif
#if ENABLED(PIDTEMP)
typedef struct PIDHeaterInfo<hotend_pid_t> hotend_info_t;
#elif ENABLED(MPCTEMP)
typedef struct MPCHeaterInfo hotend_info_t;
#else
typedef heater_info_t hotend_info_t;
#endif
@ -489,10 +516,14 @@ class Temperature {
#endif
#if ENABLED(PID_EXTRUSION_SCALING)
static int32_t last_e_position, lpq[LPQ_MAX_LEN];
static int32_t pes_e_position, lpq[LPQ_MAX_LEN];
static lpq_ptr_t lpq_ptr;
#endif
#if ENABLED(MPCTEMP)
static int32_t mpc_e_position;
#endif
#if HAS_HOTEND
static temp_range_t temp_range[HOTENDS];
#endif
@ -932,12 +963,16 @@ class Temperature {
*/
#if ENABLED(PIDTEMP)
static void updatePID() {
TERN_(PID_EXTRUSION_SCALING, last_e_position = 0);
TERN_(PID_EXTRUSION_SCALING, pes_e_position = 0);
}
#endif
#endif
#if ENABLED(MPCTEMP)
void MPC_autotune();
#endif
#if ENABLED(PROBING_HEATERS_OFF)
static void pause_heaters(const bool p);
#endif

View File

@ -219,6 +219,7 @@ HAS_EXTRUDERS = src_filter=+<src/gcode/units/M82_M83.cp
HAS_TEMP_PROBE = src_filter=+<src/gcode/temp/M192.cpp>
HAS_COOLER = src_filter=+<src/gcode/temp/M143_M193.cpp>
AUTO_REPORT_TEMPERATURES = src_filter=+<src/gcode/temp/M155.cpp>
MPCTEMP = src_filter=+<src/gcode/temp/M306.cpp>
INCH_MODE_SUPPORT = src_filter=+<src/gcode/units/G20_G21.cpp>
TEMPERATURE_UNITS_SUPPORT = src_filter=+<src/gcode/units/M149.cpp>
NEED_HEX_PRINT = src_filter=+<src/libs/hex_print.cpp>

View File

@ -240,6 +240,7 @@ default_src_filter = +<src/*> -<src/config> -<src/HAL> +<src/HAL/shared>
-<src/gcode/temp/M123.cpp>
-<src/gcode/temp/M155.cpp>
-<src/gcode/temp/M192.cpp>
-<src/gcode/temp/M306.cpp>
-<src/gcode/units/G20_G21.cpp>
-<src/gcode/units/M82_M83.cpp>
-<src/gcode/units/M149.cpp>