🔨 Single precision float

This commit is contained in:
Scott Lahteine 2025-12-12 17:09:13 -06:00
parent b99f5c3618
commit 89379cd373
9 changed files with 4 additions and 10 deletions

View file

@ -271,7 +271,7 @@ void MarlinHAL::adc_start(const pin_t pin) {
uint32_t mv;
esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);
adc_result = mv * isr_float_t(1023) / isr_float_t(ADC_REFERENCE_VOLTAGE) / isr_float_t(1000);
adc_result = (mv * 1023) * (1000.f / (ADC_REFERENCE_VOLTAGE));
// Change the attenuation level based on the new reading
adc_atten_t atten;

View file

@ -76,7 +76,6 @@
// Types
// ------------------------
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef int16_t pin_t;
typedef struct pwm_pin {

View file

@ -57,7 +57,6 @@
#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

View file

@ -63,8 +63,6 @@
// Types
// ------------------------
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef int32_t pin_t; // Parity with platform/ststm32
class libServo;

View file

@ -19,7 +19,6 @@ if __name__ == "__main__":
"-fsigned-char",
"-fno-move-loop-invariants",
"-fno-strict-aliasing",
"-fsingle-precision-constant",
"--specs=nano.specs",
"--specs=nosys.specs",

View file

@ -14,7 +14,7 @@ if pioutil.is_pio_build():
# "-Wno-sign-compare",
"-fno-sized-deallocation"
]
if "teensy" not in env["PIOENV"]:
if "teensy" not in env["PIOENV"] and "esp32" not in env["PIOENV"]:
cxxflags += ["-Wno-register"]
env.Append(CXXFLAGS=cxxflags)
env.Append(CFLAGS=["-Wno-implicit-function-declaration"])

View file

@ -17,7 +17,7 @@ platform = espressif32@2.1.0
platform_packages = espressif/toolchain-xtensa-esp32s3
board = esp32dev
build_flags = ${common.build_flags} -DCORE_DEBUG_LEVEL=0 -std=gnu++17
build_unflags = -std=gnu11 -std=gnu++11
build_unflags = -std=gnu11 -std=gnu++11 -fsingle-precision-constant -Wno-register
build_src_filter = ${common.default_src_filter} +<src/HAL/ESP32>
lib_ignore = NativeEthernet, AsyncTCP_RP2040W
upload_speed = 500000

View file

@ -39,7 +39,6 @@ build_flags = ${gd32_base.build_flags}
-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

View file

@ -47,7 +47,7 @@ extra_configs =
#
[common]
build_flags = -g3 -D__MARLIN_FIRMWARE__ -DNDEBUG
-fmax-errors=5
-fmax-errors=5 -fsingle-precision-constant
extra_scripts =
pre:buildroot/share/PlatformIO/scripts/configuration.py
pre:buildroot/share/PlatformIO/scripts/common-dependencies.py