1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00

Removing -fsingle-precision-constant (#14444)

* Removing -fsingle-precision-constant

This is so that -Wdouble-promotion raises a warning as it should.

* Adding -Wunsuffixed-float-constants

* Not ideal.

* Moving to a named constant

* Named constant update

* Using M_PIf

* Updated following feedback from @ledvinap
This commit is contained in:
Jay Blackman 2025-06-18 04:45:47 +10:00 committed by GitHub
parent 2f9ee19cbf
commit 7fed816cb3
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
27 changed files with 64 additions and 68 deletions

View file

@ -9,9 +9,7 @@
#endif
#include <math.h>
#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);

View file

@ -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};

View file

@ -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;