mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +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:
parent
2f9ee19cbf
commit
7fed816cb3
27 changed files with 64 additions and 68 deletions
|
@ -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);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue