diff --git a/lib/main/MAVLink/mavlink_conversions.h b/lib/main/MAVLink/mavlink_conversions.h index a99c541426..43462381f4 100644 --- a/lib/main/MAVLink/mavlink_conversions.h +++ b/lib/main/MAVLink/mavlink_conversions.h @@ -9,9 +9,7 @@ #endif #include -#ifndef M_PI_2 - #define M_PI_2 ((float)asin(1)) -#endif +#define MAVLINK_EPS (0.001f) /** * @file mavlink_conversions.h @@ -70,12 +68,12 @@ MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, flo float phi, theta, psi; theta = asinf(-dcm[2][0]); - if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { + if (fabsf(theta - M_PIf / 2.0f) < MAVLINK_EPS) { phi = 0.0f; psi = (atan2f(dcm[1][2] - dcm[0][1], dcm[0][2] + dcm[1][1]) + phi); - } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { + } else if (fabsf(theta + M_PIf / 2.0f) < MAVLINK_EPS) { phi = 0.0f; psi = atan2f(dcm[1][2] - dcm[0][1], dcm[0][2] + dcm[1][1] - phi); diff --git a/lib/main/google/olc/olc.c b/lib/main/google/olc/olc.c index df12775727..a4016bd74b 100644 --- a/lib/main/google/olc/olc.c +++ b/lib/main/google/olc/olc.c @@ -106,8 +106,8 @@ int OLC_Encode(const OLC_LatLon* location, size_t length, char* code, // floating point operations. long long int lat_val = kLatMaxDegrees * 2.5e7; long long int lng_val = kLonMaxDegrees * 8.192e6; - lat_val += latitude * 2.5e7; - lng_val += longitude * 8.192e6; + lat_val += latitude * 2.5e7f; + lng_val += longitude * 8.192e6f; size_t pos = kMaximumDigitCount; // Compute the grid part of the code if necessary. @@ -202,7 +202,7 @@ int OLC_Shorten(const char* code, size_t size, const OLC_LatLon* reference, // Yes, magic numbers... sob. int start = 0; - const double safety_factor = 0.3; + const double safety_factor = 0.3f; const int removal_lengths[3] = {8, 6, 4}; for (int j = 0; j < sizeof(removal_lengths) / sizeof(removal_lengths[0]); ++j) { @@ -255,10 +255,10 @@ int OLC_RecoverNearest(const char* short_code, size_t size, } // The resolution (height and width) of the padded area in degrees. - double resolution = pow_neg(kEncodingBase, 2.0 - (padding_length / 2.0)); + double resolution = pow_neg(kEncodingBase, 2.0f - (padding_length / 2.0f)); // Distance from the center to an edge (in degrees). - double half_res = resolution / 2.0; + double half_res = resolution / 2.0f; // Use the reference location to pad the supplied short code and decode it. OLC_LatLon latlon = {lat, lon}; diff --git a/lib/main/google/olc/olc_private.h b/lib/main/google/olc/olc_private.h index 2c00edcdf3..0ca45d5439 100644 --- a/lib/main/google/olc/olc_private.h +++ b/lib/main/google/olc/olc_private.h @@ -38,9 +38,9 @@ static const size_t kSeparatorPosition = 8; static const size_t kPairPrecisionInverse = 8000; // Inverse (1/) of the precision of the final grid digits in degrees. // Latitude is kEncodingBase^3 * kGridRows^kGridCodeLength -static const size_t kGridLatPrecisionInverse = 2.5e7; +static const size_t kGridLatPrecisionInverse = 2.5e7f; // Longitude is kEncodingBase^3 * kGridColumns^kGridCodeLength -static const size_t kGridLonPrecisionInverse = 8.192e6; +static const size_t kGridLonPrecisionInverse = 8.192e6f; // Latitude bounds are -kLatMaxDegrees degrees and +kLatMaxDegrees degrees // which we transpose to 0 and 180 degrees. static const double kLatMaxDegrees = OLC_kLatMaxDegrees; diff --git a/src/main/drivers/barometer/barometer_qmp6988.c b/src/main/drivers/barometer/barometer_qmp6988.c index 6369891185..cca0fa78f4 100644 --- a/src/main/drivers/barometer/barometer_qmp6988.c +++ b/src/main/drivers/barometer/barometer_qmp6988.c @@ -243,22 +243,22 @@ bool qmp6988Detect(baroDev_t *baro) else Coe_a0_ = temp2; - qmp6988_cal.Coe_a0=(float)Coe_a0_/16.0; - qmp6988_cal.Coe_a1=(-6.30E-03)+(4.30E-04)*(float)Coe_a1_/32767.0; - qmp6988_cal.Coe_a2=(-1.9E-11)+(1.2E-10)*(float)Coe_a2_/32767.0; + qmp6988_cal.Coe_a0 = (float)Coe_a0_/16.0f; + qmp6988_cal.Coe_a1 = (-6.30E-03f)+(4.30E-04f)*(float)Coe_a1_/32767.0f; + qmp6988_cal.Coe_a2 = (-1.9E-11f)+(1.2E-10f)*(float)Coe_a2_/32767.0f; - qmp6988_cal.Coe_b00 = Coe_b00_/16.0; - qmp6988_cal.Coe_bt1 = (1.00E-01)+(9.10E-02)*(float)Coe_bt1_/32767.0; - qmp6988_cal.Coe_bt2= (1.20E-08)+(1.20E-06)*(float)Coe_bt2_/32767.0; + qmp6988_cal.Coe_b00 = Coe_b00_/16.0f; + qmp6988_cal.Coe_bt1 = (1.00E-01f)+(9.10E-02f)*(float)Coe_bt1_/32767.0f; + qmp6988_cal.Coe_bt2 = (1.20E-08f)+(1.20E-06f)*(float)Coe_bt2_/32767.0f; - qmp6988_cal.Coe_bp1 = (3.30E-02)+(1.90E-02)*(float)Coe_bp1_/32767.0; - qmp6988_cal.Coe_b11= (2.10E-07)+(1.40E-07)*(float)Coe_b11_/32767.0; + qmp6988_cal.Coe_bp1 = (3.30E-02f)+(1.90E-02f)*(float)Coe_bp1_/32767.0f; + qmp6988_cal.Coe_b11 = (2.10E-07f)+(1.40E-07f)*(float)Coe_b11_/32767.0f; - qmp6988_cal.Coe_bp2 = (-6.30E-10)+(3.50E-10)*(float)Coe_bp2_/32767.0; - qmp6988_cal.Coe_b12= (2.90E-13)+(7.60E-13)*(float)Coe_b12_/32767.0; + qmp6988_cal.Coe_bp2 = (-6.30E-10f)+(3.50E-10f)*(float)Coe_bp2_/32767.0f; + qmp6988_cal.Coe_b12 = (2.90E-13f)+(7.60E-13f)*(float)Coe_b12_/32767.0f; - qmp6988_cal.Coe_b21 = (2.10E-15)+(1.20E-14)*(float)Coe_b21_/32767.0; - qmp6988_cal.Coe_bp3= (1.30E-16)+(7.90E-17)*(float)Coe_bp3_/32767.0; + qmp6988_cal.Coe_b21 = (2.10E-15f)+(1.20E-14f)*(float)Coe_b21_/32767.0f; + qmp6988_cal.Coe_bp3 = (1.30E-16f)+(7.90E-17f)*(float)Coe_bp3_/32767.0f; // Set power mode and sample times busWriteRegister(dev, QMP6988_CTRL_MEAS_REG, QMP6988_PWR_SAMPLE_MODE); diff --git a/src/main/drivers/rx/rx_sx127x.c b/src/main/drivers/rx/rx_sx127x.c index 96616b4696..bd0fde5c0f 100644 --- a/src/main/drivers/rx/rx_sx127x.c +++ b/src/main/drivers/rx/rx_sx127x.c @@ -305,25 +305,25 @@ uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw) { switch (bw) { case SX127x_BW_7_80_KHZ: - return 7.8E3; + return 7.8E3f; case SX127x_BW_10_40_KHZ: - return 10.4E3; + return 10.4E3f; case SX127x_BW_15_60_KHZ: - return 15.6E3; + return 15.6E3f; case SX127x_BW_20_80_KHZ: - return 20.8E3; + return 20.8E3f; case SX127x_BW_31_25_KHZ: - return 31.25E3; + return 31.25E3f; case SX127x_BW_41_70_KHZ: - return 41.7E3; + return 41.7E3f; case SX127x_BW_62_50_KHZ: - return 62.5E3; + return 62.5E3f; case SX127x_BW_125_00_KHZ: - return 125E3; + return 125E3f; case SX127x_BW_250_00_KHZ: - return 250E3; + return 250E3f; case SX127x_BW_500_00_KHZ: - return 500E3; + return 500E3f; } return -1; } diff --git a/src/main/drivers/rx/rx_sx127x.h b/src/main/drivers/rx/rx_sx127x.h index 0a0921657c..dab23f0562 100644 --- a/src/main/drivers/rx/rx_sx127x.h +++ b/src/main/drivers/rx/rx_sx127x.h @@ -292,7 +292,7 @@ typedef enum { #define SX127x_MAX_POWER 0x0F //17dBm -#define SX127x_FREQ_STEP 61.03515625 +#define SX127x_FREQ_STEP (61.03515625) // 61.03515625 Hz, used for frequency calculations #define SX127x_FREQ_CORRECTION_MAX ((int32_t)(100000 / SX127x_FREQ_STEP)) #define SX127x_FREQ_CORRECTION_MIN ((int32_t)(-100000 / SX127x_FREQ_STEP)) diff --git a/src/main/fc/core.c b/src/main/fc/core.c index 4cdcc4ba77..66784078c4 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -600,7 +600,7 @@ void tryArm(void) resetMaxFFT(); #endif - disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1e6; // start disarm timeout, will be extended when throttle is nonzero + disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1000 * 1000; // start disarm timeout, will be extended when throttle is nonzero lastArmingDisabledReason = 0; @@ -926,7 +926,7 @@ void processRxModes(timeUs_t currentTimeUs) // When armed and motors aren't spinning, do beeps and then disarm // board after delay so users without buzzer won't lose fingers. // mixTable constrains motor commands, so checking throttleStatus is enough - const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6; + const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6f; if (ARMING_FLAG(ARMED) && featureIsEnabled(FEATURE_MOTOR_STOP) && !isFixedWing() @@ -1019,7 +1019,7 @@ void processRxModes(timeUs_t currentTimeUs) #ifdef USE_ALTITUDE_HOLD // only if armed; can coexist with position hold - if (ARMING_FLAG(ARMED) + if (ARMING_FLAG(ARMED) // and not in GPS_RESCUE_MODE, to give it priority over Altitude Hold && !FLIGHT_MODE(GPS_RESCUE_MODE) // and either the alt_hold switch is activated, or are in failsafe landing mode @@ -1040,7 +1040,7 @@ void processRxModes(timeUs_t currentTimeUs) #ifdef USE_POSITION_HOLD // only if armed; can coexist with altitude hold - if (ARMING_FLAG(ARMED) + if (ARMING_FLAG(ARMED) // and not in GPS_RESCUE_MODE, to give it priority over Position Hold && !FLIGHT_MODE(GPS_RESCUE_MODE) // and either the alt_hold switch is activated, or are in failsafe landing mode @@ -1254,7 +1254,7 @@ static FAST_CODE_NOINLINE void subTaskPidSubprocesses(timeUs_t currentTimeUs) } #ifdef USE_TELEMETRY -#define GYRO_TEMP_READ_DELAY_US 3e6 // Only read the gyro temp every 3 seconds +#define GYRO_TEMP_READ_DELAY_US (3 * 1000 * 1000) // Only read the gyro temp every 3 seconds void subTaskTelemetryPollSensors(timeUs_t currentTimeUs) { static timeUs_t lastGyroTempTimeUs = 0; diff --git a/src/main/fc/rc.c b/src/main/fc/rc.c index 16216ad695..0e00907c5a 100644 --- a/src/main/fc/rc.c +++ b/src/main/fc/rc.c @@ -263,8 +263,8 @@ static void scaleRawSetpointToFpvCamAngle(void) { //recalculate sin/cos only when rxConfig()->fpvCamAngleDegrees changed static uint8_t lastFpvCamAngleDegrees = 0; - static float cosFactor = 1.0; - static float sinFactor = 0.0; + static float cosFactor = 1.0f; + static float sinFactor = 0.0f; if (lastFpvCamAngleDegrees != rxConfig()->fpvCamAngleDegrees) { lastFpvCamAngleDegrees = rxConfig()->fpvCamAngleDegrees; diff --git a/src/main/fc/rc_modes.c b/src/main/fc/rc_modes.c index 03d7433aa6..68dbce9664 100644 --- a/src/main/fc/rc_modes.c +++ b/src/main/fc/rc_modes.c @@ -44,7 +44,7 @@ #include "rc_modes.h" -#define STICKY_MODE_BOOT_DELAY_US 5e6 +#define STICKY_MODE_BOOT_DELAY_US (5 * 1000 * 1000) boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e static boxBitmask_t stickyModesEverDisabled; diff --git a/src/main/flight/mixer_init.c b/src/main/flight/mixer_init.c index e1d0eafe39..2b0b05caf6 100644 --- a/src/main/flight/mixer_init.c +++ b/src/main/flight/mixer_init.c @@ -371,7 +371,7 @@ void mixerInitProfile(void) mixerRuntime.rpmLimiterPGain = mixerConfig()->rpm_limit_p * 15e-6f; mixerRuntime.rpmLimiterIGain = mixerConfig()->rpm_limit_i * 1e-3f * pidGetDT(); mixerRuntime.rpmLimiterDGain = mixerConfig()->rpm_limit_d * 3e-7f * pidGetPidFrequency(); - mixerRuntime.rpmLimiterI = 0.0; + mixerRuntime.rpmLimiterI = 0.0f; pt1FilterInit(&mixerRuntime.rpmLimiterAverageRpmFilter, pt1FilterGain(6.0f, pidGetDT())); pt1FilterInit(&mixerRuntime.rpmLimiterThrottleScaleOffsetFilter, pt1FilterGain(2.0f, pidGetDT())); mixerResetRpmLimiter(); @@ -385,7 +385,7 @@ void mixerInitProfile(void) #ifdef USE_RPM_LIMIT void mixerResetRpmLimiter(void) { - mixerRuntime.rpmLimiterI = 0.0; + mixerRuntime.rpmLimiterI = 0.0f; mixerRuntime.rpmLimiterThrottleScale = constrainf(mixerRuntime.rpmLimiterRpmLimit / motorEstimateMaxRpm(), 0.0f, 1.0f); mixerRuntime.rpmLimiterInitialThrottleScale = mixerRuntime.rpmLimiterThrottleScale; } diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 74917f1c87..8c2e977205 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -105,7 +105,7 @@ static uint8_t previousProfileColorIndex = COLOR_UNDEFINED; // Decay the estimated max task duration by 1/(1 << LED_EXEC_TIME_SHIFT) on every invocation #define LED_EXEC_TIME_SHIFT 7 -#define PROFILE_COLOR_UPDATE_INTERVAL_US 1e6 // normally updates when color changes but this is a 1 second forced update +#define PROFILE_COLOR_UPDATE_INTERVAL_US 1e6f // normally updates when color changes but this is a 1 second forced update #define VISUAL_BEEPER_COLOR COLOR_WHITE diff --git a/src/main/osd/osd.c b/src/main/osd/osd.c index 6825191585..def69175a6 100644 --- a/src/main/osd/osd.c +++ b/src/main/osd/osd.c @@ -1196,7 +1196,7 @@ static timeDelta_t osdShowArmed(void) uint8_t midRow = osdDisplayPort->rows / 2; uint8_t midCol = osdDisplayPort->cols / 2; osdDrawLogo(midCol - (OSD_LOGO_COLS) / 2, midRow - 5, osdConfig()->arming_logo); - ret = osdConfig()->logo_on_arming_duration * 1e5; + ret = osdConfig()->logo_on_arming_duration * 100 * 1000; // convert to microseconds } else { ret = (REFRESH_1S / 2); } diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index da59d7fae1..f0a79da516 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -799,7 +799,7 @@ static void osdElementUpDownReference(osdElementParms_t *element) char *symbol[2] = {"U", "D"}; // character buffer int direction; - if(attitude.values.pitch>0.0){ //nose down + if (attitude.values.pitch > 0.0f){ //nose down thetaB = -earthUpinBodyFrame[2]; // get pitch w/re to nadir (use small angle approx for sine) psiB = -earthUpinBodyFrame[1]; // calculate the yaw w/re to nadir (use small angle approx for sine) direction = DOWN; @@ -1589,7 +1589,7 @@ static void osdElementRemainingTimeEstimate(osdElementParms_t *element) element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } - if (mAhDrawn <= 0.1 * osdConfig()->cap_alarm) { // also handles the mAhDrawn == 0 condition + if (mAhDrawn <= 0.1f * osdConfig()->cap_alarm) { // also handles the mAhDrawn == 0 condition tfp_sprintf(element->buff, "--:--"); } else if (mAhDrawn > osdConfig()->cap_alarm) { tfp_sprintf(element->buff, "00:00"); diff --git a/src/main/rx/expresslrs_common.h b/src/main/rx/expresslrs_common.h index cbeadd0ba2..be3f25e2bb 100644 --- a/src/main/rx/expresslrs_common.h +++ b/src/main/rx/expresslrs_common.h @@ -52,7 +52,7 @@ #define ELRS_MODELMATCH_MASK 0x3F #define FREQ_HZ_TO_REG_VAL_900(freq) ((uint32_t)(freq / SX127x_FREQ_STEP)) -#define FREQ_HZ_TO_REG_VAL_24(freq) ((uint32_t)(freq / SX1280_FREQ_STEP)) +#define FREQ_HZ_TO_REG_VAL_24(freq) ((uint32_t)(freq / SX1280_FREQ_STEP)) #define ELRS_RATE_MAX_24 6 #define ELRS_RATE_MAX_900 4 diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index 70a947a666..45ab1465ec 100644 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -667,7 +667,7 @@ FAST_CODE void scheduler(void) minGyroPeriod = gyroCyclesNow; } // Crude detection of missed cycles caused by configurator traffic - if ((gyroCyclesNow > maxGyroPeriod) && (gyroCyclesNow < (1.5 * minGyroPeriod))) { + if ((gyroCyclesNow > maxGyroPeriod) && (gyroCyclesNow < minGyroPeriod + minGyroPeriod / 2)) { // 1.5 * minGyroPeriod maxGyroPeriod = gyroCyclesNow; } } diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 8728c16b26..e9e55c9c62 100644 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -52,8 +52,8 @@ #define TASK_AGE_EXPEDITE_RX schedulerConfig()->rxRelaxDeterminism // Make RX tasks more schedulable if it's failed to be scheduled this many times #define TASK_AGE_EXPEDITE_OSD schedulerConfig()->osdRelaxDeterminism // Make OSD tasks more schedulable if it's failed to be scheduled this many times -#define TASK_AGE_EXPEDITE_COUNT 1 // Make aged tasks more schedulable -#define TASK_AGE_EXPEDITE_SCALE 0.9 // By scaling their expected execution time +#define TASK_AGE_EXPEDITE_COUNT 1 // Make aged tasks more schedulable +#define TASK_AGE_EXPEDITE_SCALE 0.9f // By scaling their expected execution time // Gyro interrupt counts over which to measure loop time and skew #define GYRO_RATE_COUNT 25000 diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 43e7463a66..9a328eff6e 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -242,7 +242,7 @@ void batteryUpdatePresence(void) batteryCriticalVoltage = 0; batteryWarningHysteresisVoltage = 0; batteryCriticalHysteresisVoltage = 0; - wattHoursDrawn = 0.0; + wattHoursDrawn = 0.0f; } } diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 281aa27ba7..a293c2d611 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -376,7 +376,7 @@ bool compassInit(void) if (magDev.magOdrHz) { // For Mags that send data at a fixed ODR, we wait some quiet period after a read before checking for new data // allow two re-check intervals, plus a margin for clock variations in mag vs FC - uint16_t odrInterval = 1e6 / magDev.magOdrHz; + uint16_t odrInterval = (1000 * 1000) / magDev.magOdrHz; compassReadIntervalUs = odrInterval - (2 * COMPASS_RECHECK_INTERVAL_US) - (odrInterval / 20); } else { // Mags which have no specified ODR will be pinged at the compass task rate @@ -522,7 +522,7 @@ uint32_t compassUpdate(timeUs_t currentTimeUs) static timeUs_t previousTimeUs = 0; const timeDelta_t dataIntervalUs = cmpTimeUs(currentTimeUs, previousTimeUs); // time since last data received previousTimeUs = currentTimeUs; - const uint16_t actualCompassDataRateHz = 1e6 / dataIntervalUs; + const uint16_t actualCompassDataRateHz = 1e6f / dataIntervalUs; timeDelta_t executeTimeUs = micros() - currentTimeUs; DEBUG_SET(DEBUG_MAG_TASK_RATE, 0, TASK_COMPASS_RATE_HZ); DEBUG_SET(DEBUG_MAG_TASK_RATE, 1, actualCompassDataRateHz); diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 497f29e75a..ea775648d1 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -413,7 +413,7 @@ static void mavlinkSendHUDAndHeartbeat(void) } #endif - mavAltitude = getEstimatedAltitudeCm() / 100.0; + mavAltitude = getEstimatedAltitudeCm() / 100.0f; mavlink_msg_vfr_hud_pack(0, 200, &mavMsg, // airspeed Current airspeed in m/s diff --git a/src/platform/APM32/mk/APM32F4.mk b/src/platform/APM32/mk/APM32F4.mk index 8bdb4b6cf7..508d4f95a7 100644 --- a/src/platform/APM32/mk/APM32F4.mk +++ b/src/platform/APM32/mk/APM32F4.mk @@ -127,7 +127,7 @@ INCLUDE_DIRS += \ $(SRC_DIR)/msc #Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant +ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 DEVICE_FLAGS = -DUSE_DAL_DRIVER -DHSE_VALUE=$(HSE_VALUE) -DAPM32 diff --git a/src/platform/AT32/mk/AT32F4.mk b/src/platform/AT32/mk/AT32F4.mk index f78c4671c9..4fc8e30726 100644 --- a/src/platform/AT32/mk/AT32F4.mk +++ b/src/platform/AT32/mk/AT32F4.mk @@ -78,7 +78,7 @@ else LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xg.ld endif -ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion +ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE MCU_COMMON_SRC = \ diff --git a/src/platform/SIMULATOR/sitl.c b/src/platform/SIMULATOR/sitl.c index 2fc992cb45..638f799d00 100644 --- a/src/platform/SIMULATOR/sitl.c +++ b/src/platform/SIMULATOR/sitl.c @@ -425,8 +425,7 @@ uint64_t micros64(void) out += (now - last) * simRate; last = now; - return out*1e-3; -// return micros64_real(); + return out / 1000; } uint64_t millis64(void) @@ -438,8 +437,7 @@ uint64_t millis64(void) out += (now - last) * simRate; last = now; - return out*1e-6; -// return millis64_real(); + return out / (1000 * 1000); } uint32_t micros(void) diff --git a/src/platform/STM32/mk/STM32F4.mk b/src/platform/STM32/mk/STM32F4.mk index aa4b1d6249..adadafd80c 100644 --- a/src/platform/STM32/mk/STM32F4.mk +++ b/src/platform/STM32/mk/STM32F4.mk @@ -150,7 +150,7 @@ DEVICE_FLAGS += -DUSE_STDPERIPH_DRIVER endif #Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant +ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 ifeq ($(TARGET_MCU),STM32F411xE) DEVICE_FLAGS += -DSTM32F411xE -finline-limit=20 diff --git a/src/platform/STM32/mk/STM32F7.mk b/src/platform/STM32/mk/STM32F7.mk index 90c3291cec..0e90ff10a0 100644 --- a/src/platform/STM32/mk/STM32F7.mk +++ b/src/platform/STM32/mk/STM32F7.mk @@ -97,7 +97,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant +ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 # Flags that are used in the STM32 libraries DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER diff --git a/src/platform/STM32/mk/STM32G4.mk b/src/platform/STM32/mk/STM32G4.mk index 0706aff8fd..57e8dc51bd 100644 --- a/src/platform/STM32/mk/STM32G4.mk +++ b/src/platform/STM32/mk/STM32G4.mk @@ -90,7 +90,7 @@ INCLUDE_DIRS := \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant +ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DUSE_DMA_RAM -DMAX_MPU_REGIONS=16 diff --git a/src/platform/STM32/mk/STM32H5.mk b/src/platform/STM32/mk/STM32H5.mk index a9080ba2ed..d708a4eb88 100644 --- a/src/platform/STM32/mk/STM32H5.mk +++ b/src/platform/STM32/mk/STM32H5.mk @@ -99,7 +99,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant +ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 # Flags that are used in the STM32 libraries DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER diff --git a/src/platform/STM32/mk/STM32H7.mk b/src/platform/STM32/mk/STM32H7.mk index 7d192ff057..4a5c371d77 100644 --- a/src/platform/STM32/mk/STM32H7.mk +++ b/src/platform/STM32/mk/STM32H7.mk @@ -103,7 +103,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant +ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 # Flags that are used in the STM32 libraries DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER