From 0542fb70b512e7fcd0de42b905f03abdded2b587 Mon Sep 17 00:00:00 2001 From: James Aguilar Date: Sun, 26 Apr 2026 20:23:17 -0600 Subject: [PATCH] Replace double literals and fns with floats. In all cases, these literals are intended to be used in floating point operations. Floating point acceleration is much more common on devices where SimpleFOC runs. Even where no acceleration is present, soft floats are universally more efficient than soft doubles. Additionally, fix several cases where fabs or flog are used instead of fabsf or flogf. --- src/common/base_classes/CurrentSense.cpp | 16 +++---- src/common/base_classes/FOCMotor.cpp | 12 ++--- src/common/base_classes/FOCMotor.h | 2 +- src/common/base_classes/Sensor.h | 2 +- .../esp32/esp32_mcpwm_mcu.cpp | 2 +- .../hardware_specific/generic_mcu.cpp | 2 +- .../hardware_specific/samd/samd21_mcu.cpp | 2 +- .../hardware_specific/teensy/teensy4_mcu.cpp | 4 +- .../atmega/atmega2560_mcu.cpp | 10 ++--- .../atmega/atmega328_mcu.cpp | 10 ++--- .../atmega/atmega32u4_mcu.cpp | 6 +-- .../esp32/esp32_driver_mcpwm.cpp | 4 +- .../esp32/esp32_ledc_mcu.cpp | 6 +-- src/drivers/hardware_specific/nrf52_mcu.cpp | 2 +- .../hardware_specific/portenta_h7_mcu.cpp | 12 ++--- .../hardware_specific/renesas/renesas.cpp | 44 +++++++++---------- .../hardware_specific/rp2040/rp2040_mcu.cpp | 2 +- .../hardware_specific/samd/samd21_mcu.cpp | 4 +- .../hardware_specific/samd/samd51_mcu.cpp | 2 +- .../hardware_specific/samd/samd_mcu.cpp | 12 ++--- 20 files changed, 78 insertions(+), 78 deletions(-) diff --git a/src/common/base_classes/CurrentSense.cpp b/src/common/base_classes/CurrentSense.cpp index 85ebd2c5..7ba85507 100644 --- a/src/common/base_classes/CurrentSense.cpp +++ b/src/common/base_classes/CurrentSense.cpp @@ -202,12 +202,12 @@ int CurrentSense::alignBLDCDriver(float voltage, BLDCDriver* bldc_driver, bool m bool phases_inverted = 0; float zero = 0; - if(modulation_centered) zero = driver->voltage_limit/2.0; + if(modulation_centered) zero = driver->voltage_limit/2.0f; // set phase A active and phases B and C down // 300 ms of ramping for(int i=0; i < 100; i++){ - bldc_driver->setPwm(voltage/100.0*((float)i)+zero , zero, zero); + bldc_driver->setPwm(voltage/100.0f*((float)i)+zero , zero, zero); _delay(3); } _delay(500); @@ -318,7 +318,7 @@ int CurrentSense::alignBLDCDriver(float voltage, BLDCDriver* bldc_driver, bool m // set phase B active and phases A and C down // 300 ms of ramping for(int i=0; i < 100; i++){ - bldc_driver->setPwm(zero, voltage/100.0*((float)i)+zero, zero); + bldc_driver->setPwm(zero, voltage/100.0f*((float)i)+zero, zero); _delay(3); } _delay(500); @@ -430,7 +430,7 @@ int CurrentSense::alignStepperDriver(float voltage, StepperDriver* stepper_drive // set phase A active and phases B down // ramp 300ms for(int i=0; i < 100; i++){ - stepper_driver->setPwm(voltage/100.0*((float)i), 0); + stepper_driver->setPwm(voltage/100.0f*((float)i), 0); _delay(3); } _delay(500); @@ -465,7 +465,7 @@ int CurrentSense::alignStepperDriver(float voltage, StepperDriver* stepper_drive // set phase B active and phases A down // ramp 300ms for(int i=0; i < 100; i++){ - stepper_driver->setPwm(0, voltage/100.0*((float)i)); + stepper_driver->setPwm(0, voltage/100.0f*((float)i)); _delay(3); } _delay(500); @@ -511,7 +511,7 @@ int CurrentSense::alignHybridDriver(float voltage, BLDCDriver* bldc_driver, bool // set phase A active and phases B active, and C down // ramp 300ms for(int i=0; i < 100; i++){ - bldc_driver->setPwm(voltage/100.0*((float)i), voltage/100.0*((float)i), 0); + bldc_driver->setPwm(voltage/100.0f*((float)i), voltage/100.0f*((float)i), 0); _delay(3); } _delay(500); @@ -601,7 +601,7 @@ int CurrentSense::alignHybridDriver(float voltage, BLDCDriver* bldc_driver, bool // set phase A active and phases B down // ramp 300ms for(int i=0; i < 100; i++){ - bldc_driver->setPwm(voltage/100.0*((float)i), 0, 0); + bldc_driver->setPwm(voltage/100.0f*((float)i), 0, 0); _delay(3); } _delay(500); @@ -682,7 +682,7 @@ int CurrentSense::alignHybridDriver(float voltage, BLDCDriver* bldc_driver, bool // set phase B active and phases A down // ramp 300ms for(int i=0; i < 100; i++){ - bldc_driver->setPwm(0, voltage/100.0*((float)i), 0); + bldc_driver->setPwm(0, voltage/100.0f*((float)i), 0); _delay(3); } _delay(500); diff --git a/src/common/base_classes/FOCMotor.cpp b/src/common/base_classes/FOCMotor.cpp index a193229a..5363b2a1 100644 --- a/src/common/base_classes/FOCMotor.cpp +++ b/src/common/base_classes/FOCMotor.cpp @@ -122,7 +122,7 @@ int FOCMotor::characteriseMotor(float voltage, float correction_factor=1.0f){ // 300 ms of ramping current_electric_angle = electricalAngle(); for(int i=0; i < 100; i++){ - setPhaseVoltage(0, voltage/100.0*((float)i), current_electric_angle); + setPhaseVoltage(0, voltage/100.0f*((float)i), current_electric_angle); _delay(3); } _delay(10); @@ -205,7 +205,7 @@ int FOCMotor::characteriseMotor(float voltage, float correction_factor=1.0f){ continue; } - inductanced += fabsf(- (resistance * dt) / log((voltage - resistance * (l_currents.d - zerocurrent.d)) / voltage))/correction_factor; + inductanced += fabsf(- (resistance * dt) / logf((voltage - resistance * (l_currents.d - zerocurrent.d)) / voltage))/correction_factor; qcurrent+= l_currents.q - zerocurrent.q; // average the measured currents dcurrent+= l_currents.d - zerocurrent.d; @@ -217,7 +217,7 @@ int FOCMotor::characteriseMotor(float voltage, float correction_factor=1.0f){ inductanced /= cycles; - Ltemp = i < 2 ? inductanced : Ltemp * 0.6 + inductanced * 0.4; + Ltemp = i < 2 ? inductanced : Ltemp * 0.6f + inductanced * 0.4f; float timeconstant = fabsf(Ltemp / resistance); // Timeconstant of an RL circuit (L/R) // SIMPLEFOC_MOTOR_DEBUG("Estimated time constant in us: ", 1000000.0f * timeconstant); @@ -254,7 +254,7 @@ int FOCMotor::characteriseMotor(float voltage, float correction_factor=1.0f){ // Average the d-axis angle further for calculating the electrical zero later if (axis) { - d_electrical_angle = i < 2 ? current_electric_angle : d_electrical_angle * 0.9 + current_electric_angle * 0.1; + d_electrical_angle = i < 2 ? current_electric_angle : d_electrical_angle * 0.9f + current_electric_angle * 0.1f; } } @@ -883,7 +883,7 @@ int FOCMotor::alignSensor() { // setPhaseVoltage(0, 0, 0); _delay(200); // determine the direction the sensor moved - float moved = fabs(mid_angle - end_angle); + float moved = fabsf(mid_angle - end_angle); if (moved 0.5f); // 0.5f is arbitrary number it can be lower or higher! + pp_check_result = !(fabsf(moved*pole_pairs - _2PI) > 0.5f); // 0.5f is arbitrary number it can be lower or higher! if( pp_check_result==false ) { SIMPLEFOC_MOTOR_WARN("PP check: fail - est. pp: ", _2PI/moved); } else { diff --git a/src/common/base_classes/FOCMotor.h b/src/common/base_classes/FOCMotor.h index e769c0fa..0bb2f7ec 100644 --- a/src/common/base_classes/FOCMotor.h +++ b/src/common/base_classes/FOCMotor.h @@ -260,7 +260,7 @@ class FOCMotor PIDController PID_velocity{DEF_PID_VEL_P,DEF_PID_VEL_I,DEF_PID_VEL_D,DEF_PID_VEL_RAMP,DEF_PID_VEL_LIMIT};//!< parameter determining the velocity PID configuration PIDController P_angle{DEF_P_ANGLE_P,0,0,0,DEF_VEL_LIM}; //!< parameter determining the position PID configuration LowPassFilter LPF_velocity{DEF_VEL_FILTER_Tf};//!< parameter determining the velocity Low pass filter configuration - LowPassFilter LPF_angle{0.0};//!< parameter determining the angle low pass filter configuration + LowPassFilter LPF_angle{0.0f};//!< parameter determining the angle low pass filter configuration unsigned int motion_downsample = DEF_MOTION_DOWNSMAPLE; //!< parameter defining the ratio of downsampling for move commad unsigned int motion_cnt = 0; //!< counting variable for downsampling for move commad diff --git a/src/common/base_classes/Sensor.h b/src/common/base_classes/Sensor.h index c77eb911..adfdc986 100644 --- a/src/common/base_classes/Sensor.h +++ b/src/common/base_classes/Sensor.h @@ -106,7 +106,7 @@ class Sensor{ /** * Minimum time between updates to velocity. If time elapsed is lower than this, the velocity is not updated. */ - float min_elapsed_time = 0.000100; // default is 100 microseconds, or 10kHz + float min_elapsed_time = 0.000100f; // default is 100 microseconds, or 10kHz protected: /** diff --git a/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp b/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp index 23c03a2c..41ded6f2 100644 --- a/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp +++ b/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp @@ -187,7 +187,7 @@ void* IRAM_ATTR _driverSyncLowSide(void* driver_params, void* cs_params){ if (cs->pretrig_comparator){ // Calculate pwm duty cycle ticks for pre-trigger channel // TODO: verify the timing it seems to be correct between 15 and 20kHz (but needs better testing) - uint32_t pwm_duty_cycle = p->mcpwm_period * (0.75 - ((float)p->pwm_frequency*SIMPLEFOC_CS_PRETRIGGER_US)/1e6/2.0); + uint32_t pwm_duty_cycle = p->mcpwm_period * (0.75f - ((float)p->pwm_frequency*SIMPLEFOC_CS_PRETRIGGER_US)/1e6f/2.0f); // set up the comparator duty cycle CHECK_CS_ERR(mcpwm_comparator_set_compare_value((mcpwm_cmpr_handle_t)cs->pretrig_comparator, pwm_duty_cycle), "Failed to set pretrigger compare value"); diff --git a/src/current_sense/hardware_specific/generic_mcu.cpp b/src/current_sense/hardware_specific/generic_mcu.cpp index ff8c467c..5e94b9e6 100644 --- a/src/current_sense/hardware_specific/generic_mcu.cpp +++ b/src/current_sense/hardware_specific/generic_mcu.cpp @@ -26,7 +26,7 @@ __attribute__((weak)) void* _configureADCInline(const void* driver_params, cons // function reading an ADC value and returning the read voltage __attribute__((weak)) float _readADCVoltageLowSide(const int pinA, const void* cs_params){ SIMPLEFOC_DEBUG("ERR: Low-side cs not supported!"); - return 0.0; + return 0.0f; } // Configure low side for generic mcu diff --git a/src/current_sense/hardware_specific/samd/samd21_mcu.cpp b/src/current_sense/hardware_specific/samd/samd21_mcu.cpp index 3a045446..238f24bc 100644 --- a/src/current_sense/hardware_specific/samd/samd21_mcu.cpp +++ b/src/current_sense/hardware_specific/samd/samd21_mcu.cpp @@ -161,7 +161,7 @@ float _readADCVoltageLowSide(const int pin, const void* cs_params) { i++; } - return 0.0; // pin not available + return 0.0f; // pin not available } void* _driverSyncLowSide(void* driver_params, void* cs_params) { diff --git a/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp b/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp index 3a542b53..ff0cc718 100644 --- a/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp +++ b/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp @@ -143,7 +143,7 @@ void adc_etc_init(int pin1, int pin2, int pin3=NOT_SET) { // function reading an ADC value and returning the read voltage float _readADCVoltageLowSide(const int pinA, const void* cs_params){ - if(!_isset(pinA)) return 0.0; // if the pin is not set return 0 + if(!_isset(pinA)) return 0.0f; // if the pin is not set return 0 GenericCurrentSenseParams* params = (GenericCurrentSenseParams*) cs_params; float adc_voltage_conv = params->adc_voltage_conv; if (pinA == params->pins[0]) { @@ -153,7 +153,7 @@ float _readADCVoltageLowSide(const int pinA, const void* cs_params){ }else if (pinA == params->pins[2]) { return val2 * adc_voltage_conv; } - return 0.0; + return 0.0f; } // Configure low side for generic mcu diff --git a/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp b/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp index 532b3ce3..80441528 100644 --- a/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp +++ b/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp @@ -17,7 +17,7 @@ void _pinHighFrequency(const int pin, const long frequency){ bool high_fq = false; // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz) // else set the 4kHz - if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; + if(frequency >= 0.5f*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; // High PWM frequency // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-ATmega2560 // https://forum.arduino.cc/index.php?topic=72092.0 @@ -170,7 +170,7 @@ int _configureComplementaryPair(const int pinH,const int pinL, long frequency) { bool high_fq = false; // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz) // else set the 4kHz - if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; + if(frequency >= 0.5f*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; // configure pin pairs if( (pinH == 4 && pinL == 13 ) || (pinH == 13 && pinL == 4 ) ){ @@ -274,9 +274,9 @@ void _setPwmPair(int pinH, int pinL, float val, int dead_time, PhaseState ps) // - hardware specific // supports Arduino/ATmega328 void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){ - _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[0]); - _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[1]); - _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[2]); + _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f, phase_state[0]); + _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f, phase_state[1]); + _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f, phase_state[2]); } #endif diff --git a/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp b/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp index 9df9b8a7..2d92f2ac 100644 --- a/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp +++ b/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp @@ -15,7 +15,7 @@ void _pinHighFrequency(const int pin, const long frequency){ bool high_fq = false; // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz) // else set the 4kHz - if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; + if(frequency >= 0.5f*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; // High PWM frequency // https://www.arxterra.com/9-atmega328p-timers/ if (pin == 5 || pin == 6 ) { @@ -167,7 +167,7 @@ int _configureComplementaryPair(const int pinH, const int pinL, long frequency) bool high_fq = false; // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz) // else set the 4kHz - if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; + if(frequency >= 0.5f*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true; // configure pins if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){ @@ -251,9 +251,9 @@ void _setPwmPair(int pinH, int pinL, float val, int dead_time, PhaseState ps) // - hardware specific // supports Arduino/ATmega328 void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){ - _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[0]); - _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[1]); - _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[2]); + _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f, phase_state[0]); + _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f, phase_state[1]); + _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f, phase_state[2]); } #endif diff --git a/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp b/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp index 4cf454ae..26dad439 100644 --- a/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp +++ b/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp @@ -216,9 +216,9 @@ void _setPwmPair(int pinH, int pinL, float val, int dead_time) // - hardware specific // supports Arudino/ATmega328 void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){ - _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0); - _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0); - _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0); + _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f); + _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f); + _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0f, ((GenericDriverParams*)params)->dead_zone*255.0f); _UNUSED(phase_state); } diff --git a/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp b/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp index 1418e34a..da42d49b 100644 --- a/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp +++ b/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp @@ -452,7 +452,7 @@ void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int shared_timer = true; } - uint8_t no_operators = ceil(no_pins / 2.0); + uint8_t no_operators = ceil(no_pins / 2.0f); SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_operators) + " operators."); mcpwm_operator_config_t operator_config = { .group_id = mcpwm_group }; operator_config.intr_priority = 0; @@ -510,7 +510,7 @@ void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int // function setting the duty cycle to the MCPWM pin void IRAM_ATTR _setDutyCycle(mcpwm_cmpr_handle_t cmpr, uint32_t mcpwm_period, float duty_cycle){ - float duty = _constrain(duty_cycle, 0.0, 1.0); + float duty = _constrain(duty_cycle, 0.0f, 1.0f); mcpwm_comparator_set_compare_value(cmpr, (uint32_t)(mcpwm_period*duty)); } diff --git a/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp b/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp index df7bd3fc..e522cc08 100644 --- a/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp +++ b/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp @@ -303,7 +303,7 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in void IRAM_ATTR _writeDutyCycle(float dc, void* params, int index){ - ledc_set_duty_with_hpoint(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index], _PWM_RES*dc, _PWM_RES/2.0*(1.0-dc)); + ledc_set_duty_with_hpoint(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index], _PWM_RES*dc, _PWM_RES/2.0f*(1.0f-dc)); ledc_update_duty(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index]); } @@ -390,8 +390,8 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons } void IRAM_ATTR _setPwmPairDutyCycle( void* params, int ind_h, int ind_l, float val, float dead_time, PhaseState ps){ - float pwm_h = _constrain(val - (dead_time * 0.5), 0, 1.0); - float pwm_l = _constrain(val + (dead_time * 0.5), 0, 1.0); + float pwm_h = _constrain(val - (dead_time * 0.5f), 0, 1.0f); + float pwm_l = _constrain(val + (dead_time * 0.5f), 0, 1.0f); // determine the phase state and set the pwm accordingly // deactivate phases if needed diff --git a/src/drivers/hardware_specific/nrf52_mcu.cpp b/src/drivers/hardware_specific/nrf52_mcu.cpp index a20b828a..3985ac15 100644 --- a/src/drivers/hardware_specific/nrf52_mcu.cpp +++ b/src/drivers/hardware_specific/nrf52_mcu.cpp @@ -13,7 +13,7 @@ #define PWM_RESOLUTION (PWM_CLK/PWM_FREQ) #define PWM_MAX_FREQ (62500) #define DEAD_ZONE (250) // in ns -#define DEAD_TIME (DEAD_ZONE / (PWM_RESOLUTION * 0.25 * 62.5)) // 62.5ns resolution of PWM +#define DEAD_TIME (DEAD_ZONE / (PWM_RESOLUTION * 0.25f * 62.5f)) // 62.5ns resolution of PWM #ifdef NRF_PWM3 #define PWM_COUNT 4 diff --git a/src/drivers/hardware_specific/portenta_h7_mcu.cpp b/src/drivers/hardware_specific/portenta_h7_mcu.cpp index e9807609..16b1a7e2 100644 --- a/src/drivers/hardware_specific/portenta_h7_mcu.cpp +++ b/src/drivers/hardware_specific/portenta_h7_mcu.cpp @@ -118,7 +118,7 @@ int _pwm_init(pwmout_t *obj, uint32_t pin, long frequency){ #endif } - long period_us = 500000.0/((float)frequency); + long period_us = 500000.0f/((float)frequency); /* By default use, 1us as SW pre-scaler */ obj->prescaler = 1; // TIMxCLK = PCLKx when the APB prescaler = 1 else TIMxCLK = 2 * PCLKx @@ -212,13 +212,13 @@ void _pwm_write(pwmout_t *obj, float value){ TimHandle.Instance = (TIM_TypeDef *)(obj->pwm); - if (value < (float)0.0) { - value = 0.0; - } else if (value > (float)1.0) { - value = 1.0; + if (value < (float)0.0f) { + value = 0.0f; + } else if (value > (float)1.0f) { + value = 1.0f; } - obj->pulse = (uint32_t)((float)obj->period * value + 0.5); + obj->pulse = (uint32_t)((float)obj->period * value + 0.5f); switch (obj->channel) { case 1: diff --git a/src/drivers/hardware_specific/renesas/renesas.cpp b/src/drivers/hardware_specific/renesas/renesas.cpp index 91405a56..107db5d8 100644 --- a/src/drivers/hardware_specific/renesas/renesas.cpp +++ b/src/drivers/hardware_specific/renesas/renesas.cpp @@ -76,48 +76,48 @@ ClockDivAndRange getClockDivAndRange(uint32_t pwm_frequency, uint8_t timer_chann uint32_t max_count = (timer_channel < GTP32_HOWMANY)? 4294967295 : 65535; uint32_t freq_hz = R_FSP_SystemClockHzGet(FSP_PRIV_CLOCK_PCLKD); float range = (float) freq_hz / ((float) pwm_frequency * 2.0f); - if(range / 1.0 < max_count) { - result.range = (uint32_t) (range / 1.0); + if(range / 1.0f < max_count) { + result.range = (uint32_t) (range / 1.0f); result.clk_div = TIMER_SOURCE_DIV_1; } - else if (range / 2.0 < max_count) { - result.range = (uint32_t) (range / 2.0); + else if (range / 2.0f < max_count) { + result.range = (uint32_t) (range / 2.0f); result.clk_div = TIMER_SOURCE_DIV_2; } - else if(range / 4.0 < max_count) { - result.range = (uint32_t) (range / 4.0); + else if(range / 4.0f < max_count) { + result.range = (uint32_t) (range / 4.0f); result.clk_div = TIMER_SOURCE_DIV_4; } - else if(range / 8.0 < max_count) { - result.range = (uint32_t) (range / 8.0 ); + else if(range / 8.0f < max_count) { + result.range = (uint32_t) (range / 8.0f ); result.clk_div = TIMER_SOURCE_DIV_8; } - else if(range / 16.0 < max_count) { - result.range = (uint32_t) (range / 16.0 ); + else if(range / 16.0f < max_count) { + result.range = (uint32_t) (range / 16.0f ); result.clk_div = TIMER_SOURCE_DIV_16; } - else if (range / 32.0 < max_count) { - result.range = (uint32_t) (range / 32.0 ); + else if (range / 32.0f < max_count) { + result.range = (uint32_t) (range / 32.0f ); result.clk_div = TIMER_SOURCE_DIV_32; } - else if(range / 64.0 < max_count) { - result.range = (uint32_t) (range / 64.0 ); + else if(range / 64.0f < max_count) { + result.range = (uint32_t) (range / 64.0f ); result.clk_div = TIMER_SOURCE_DIV_64; } - else if(range / 128.0 < max_count) { - result.range = (uint32_t) (range / 128.0 ); + else if(range / 128.0f < max_count) { + result.range = (uint32_t) (range / 128.0f ); result.clk_div = TIMER_SOURCE_DIV_128; } - else if(range / 256.0 < max_count) { - result.range = (uint32_t) (range / 256.0 ); + else if(range / 256.0f < max_count) { + result.range = (uint32_t) (range / 256.0f ); result.clk_div = TIMER_SOURCE_DIV_256; } - else if(range / 512.0 < max_count) { - result.range = (uint32_t) (range / 512.0 ); + else if(range / 512.0f < max_count) { + result.range = (uint32_t) (range / 512.0f ); result.clk_div = TIMER_SOURCE_DIV_512; } - else if(range / 1024.0 < max_count) { - result.range = (uint32_t) (range / 1024.0 ); + else if(range / 1024.0f < max_count) { + result.range = (uint32_t) (range / 1024.0f ); result.clk_div = TIMER_SOURCE_DIV_1024; } else { diff --git a/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp b/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp index 05f6eb97..f01a61d8 100644 --- a/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp +++ b/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp @@ -211,7 +211,7 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, vo inline float swDti(float val, float dt) { float ret = dt+val; - if (ret>1.0) ret = 1.0f; + if (ret>1.0f) ret = 1.0f; return ret; } diff --git a/src/drivers/hardware_specific/samd/samd21_mcu.cpp b/src/drivers/hardware_specific/samd/samd21_mcu.cpp index d59a3098..bc865052 100644 --- a/src/drivers/hardware_specific/samd/samd21_mcu.cpp +++ b/src/drivers/hardware_specific/samd/samd21_mcu.cpp @@ -245,7 +245,7 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVEB_WAVEGENB_DSBOTH; // Set wave form configuration while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync - if (hw6pwm>0.0) { + if (hw6pwm>0.0f) { tcc->WEXCTRL.vec.DTIEN |= (1<WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1); tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1); @@ -292,7 +292,7 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal; syncTCC(tcc); // wait for sync - if (hw6pwm>0.0) { + if (hw6pwm>0.0f) { tcc->WEXCTRL.vec.DTIEN |= (1<WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1); tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1); diff --git a/src/drivers/hardware_specific/samd/samd51_mcu.cpp b/src/drivers/hardware_specific/samd/samd51_mcu.cpp index 71bf0b81..619f745a 100644 --- a/src/drivers/hardware_specific/samd/samd51_mcu.cpp +++ b/src/drivers/hardware_specific/samd/samd51_mcu.cpp @@ -272,7 +272,7 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, // store for later use tccConfig.pwm_res = pwm_resolution; - if (hw6pwm>0.0) { + if (hw6pwm>0.0f) { tcc->WEXCTRL.vec.DTIEN |= (1<WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1); tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1); diff --git a/src/drivers/hardware_specific/samd/samd_mcu.cpp b/src/drivers/hardware_specific/samd/samd_mcu.cpp index 3a6581e0..23206a26 100644 --- a/src/drivers/hardware_specific/samd/samd_mcu.cpp +++ b/src/drivers/hardware_specific/samd/samd_mcu.cpp @@ -617,13 +617,13 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons // configure the TCC(s) configureTCC(pinAh, pwm_frequency, false, (pinAh.tcc.chaninfo==pinAl.tcc.chaninfo)?dead_zone:-1); if ((pinAh.tcc.chaninfo!=pinAl.tcc.chaninfo)) - configureTCC(pinAl, pwm_frequency, true, -1.0); + configureTCC(pinAl, pwm_frequency, true, -1.0f); configureTCC(pinBh, pwm_frequency, false, (pinBh.tcc.chaninfo==pinBl.tcc.chaninfo)?dead_zone:-1); if ((pinBh.tcc.chaninfo!=pinBl.tcc.chaninfo)) - configureTCC(pinBl, pwm_frequency, true, -1.0); + configureTCC(pinBl, pwm_frequency, true, -1.0f); configureTCC(pinCh, pwm_frequency, false, (pinCh.tcc.chaninfo==pinCl.tcc.chaninfo)?dead_zone:-1); if ((pinCh.tcc.chaninfo!=pinCl.tcc.chaninfo)) - configureTCC(pinCl, pwm_frequency, true, -1.0); + configureTCC(pinCl, pwm_frequency, true, -1.0f); getTccPinConfiguration(pinA_h)->pwm_res = pinAh.pwm_res; getTccPinConfiguration(pinA_l)->pwm_res = pinAh.pwm_res; // use the high phase resolution, in case we didn't set it getTccPinConfiguration(pinB_h)->pwm_res = pinBh.pwm_res; @@ -742,7 +742,7 @@ void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_ if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) { // low-side on a different pin of same TCC - do dead-time in software... float ls = dc_a+(p->dead_zone * (pwm_res-1)); // TODO resolution!!! - if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time + if (ls>1.0f) ls = 1.0f; // no off-time is better than too-short dead-time writeSAMDDutyCycle(tcc1, dc_a); writeSAMDDutyCycle(tcc2, ls); } @@ -753,7 +753,7 @@ void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_ tcc2 = p->tccPinConfigurations[3]; if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) { float ls = dc_b+(p->dead_zone * (pwm_res-1)); - if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time + if (ls>1.0f) ls = 1.0f; // no off-time is better than too-short dead-time writeSAMDDutyCycle(tcc1, dc_b); writeSAMDDutyCycle(tcc2, ls); } @@ -764,7 +764,7 @@ void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_ tcc2 = p->tccPinConfigurations[5]; if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) { float ls = dc_c+(p->dead_zone * (pwm_res-1)); - if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time + if (ls>1.0f) ls = 1.0f; // no off-time is better than too-short dead-time writeSAMDDutyCycle(tcc1, dc_c); writeSAMDDutyCycle(tcc2, ls); }