Fix use of floating point math functions

This commit is contained in:
Mathias Rasmussen 2021-12-03 03:58:19 +01:00
parent 4c034d67ee
commit 87c259a26e
9 changed files with 20 additions and 19 deletions

View File

@ -68,7 +68,7 @@ MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float d
MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
{ {
float phi, theta, psi; float phi, theta, psi;
theta = asin(-dcm[2][0]); theta = asinf(-dcm[2][0]);
if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f; phi = 0.0f;

View File

@ -324,7 +324,7 @@ static void rescueAttainPosition()
gpsRescueAngle[AI_PITCH] = constrain(gpsRescueAngle[AI_PITCH] + MIN(angleAdjustment, 80), rescueState.intent.minAngleDeg * 100, rescueState.intent.maxAngleDeg * 100); gpsRescueAngle[AI_PITCH] = constrain(gpsRescueAngle[AI_PITCH] + MIN(angleAdjustment, 80), rescueState.intent.minAngleDeg * 100, rescueState.intent.maxAngleDeg * 100);
const float ct = cos(DECIDEGREES_TO_RADIANS(gpsRescueAngle[AI_PITCH] / 10)); const float ct = cosf(DECIDEGREES_TO_RADIANS(gpsRescueAngle[AI_PITCH] / 10));
/** /**
Altitude controller Altitude controller

View File

@ -366,9 +366,9 @@ static void applyMixToMotors(float motorMix[MAX_SUPPORTED_MOTORS], motorMixer_t
motorOutput = (motorOutput < motorRangeMin) ? mixerRuntime.disarmMotorOutput : motorOutput; // Prevent getting into special reserved range motorOutput = (motorOutput < motorRangeMin) ? mixerRuntime.disarmMotorOutput : motorOutput; // Prevent getting into special reserved range
} }
#endif #endif
motorOutput = constrain(motorOutput, mixerRuntime.disarmMotorOutput, motorRangeMax); motorOutput = constrainf(motorOutput, mixerRuntime.disarmMotorOutput, motorRangeMax);
} else { } else {
motorOutput = constrain(motorOutput, motorRangeMin, motorRangeMax); motorOutput = constrainf(motorOutput, motorRangeMin, motorRangeMax);
} }
motor[i] = motorOutput; motor[i] = motorOutput;
} }

View File

@ -1233,13 +1233,14 @@ bool pidAntiGravityEnabled(void)
#ifdef USE_DYN_LPF #ifdef USE_DYN_LPF
void dynLpfDTermUpdate(float throttle) void dynLpfDTermUpdate(float throttle)
{ {
unsigned int cutoffFreq;
if (pidRuntime.dynLpfFilter != DYN_LPF_NONE) { if (pidRuntime.dynLpfFilter != DYN_LPF_NONE) {
float cutoffFreq;
if (pidRuntime.dynLpfCurveExpo > 0) { if (pidRuntime.dynLpfCurveExpo > 0) {
cutoffFreq = dynLpfCutoffFreq(throttle, pidRuntime.dynLpfMin, pidRuntime.dynLpfMax, pidRuntime.dynLpfCurveExpo); cutoffFreq = dynLpfCutoffFreq(throttle, pidRuntime.dynLpfMin, pidRuntime.dynLpfMax, pidRuntime.dynLpfCurveExpo);
} else { } else {
cutoffFreq = fmax(dynThrottle(throttle) * pidRuntime.dynLpfMax, pidRuntime.dynLpfMin); cutoffFreq = fmaxf(dynThrottle(throttle) * pidRuntime.dynLpfMax, pidRuntime.dynLpfMin);
} }
switch (pidRuntime.dynLpfFilter) { switch (pidRuntime.dynLpfFilter) {
case DYN_LPF_PT1: case DYN_LPF_PT1:
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {

View File

@ -1036,7 +1036,7 @@ static uint8_t vtxSAGetPowerLevels(const vtxDevice_t *vtxDevice, uint16_t *level
for (uint8_t i = 0; i < saSupportedNumPowerLevels; i++) { for (uint8_t i = 0; i < saSupportedNumPowerLevels; i++) {
levels[i] = saSupportedPowerValues[i]; levels[i] = saSupportedPowerValues[i];
uint16_t power = (uint16_t)pow(10.0,levels[i]/10.0); uint16_t power = (uint16_t)powf(10.0f, levels[i] / 10.0f);
if (levels[i] > 14) { if (levels[i] > 14) {
// For powers greater than 25mW round up to a multiple of 50 to match expectations // For powers greater than 25mW round up to a multiple of 50 to match expectations

View File

@ -619,13 +619,13 @@ float dynThrottle(float throttle) {
void dynLpfGyroUpdate(float throttle) void dynLpfGyroUpdate(float throttle)
{ {
if (gyro.dynLpfFilter != DYN_LPF_NONE) { if (gyro.dynLpfFilter != DYN_LPF_NONE) {
unsigned int cutoffFreq; float cutoffFreq;
if (gyro.dynLpfCurveExpo > 0) { if (gyro.dynLpfCurveExpo > 0) {
cutoffFreq = dynLpfCutoffFreq(throttle, gyro.dynLpfMin, gyro.dynLpfMax, gyro.dynLpfCurveExpo); cutoffFreq = dynLpfCutoffFreq(throttle, gyro.dynLpfMin, gyro.dynLpfMax, gyro.dynLpfCurveExpo);
} else { } else {
cutoffFreq = fmax(dynThrottle(throttle) * gyro.dynLpfMax, gyro.dynLpfMin); cutoffFreq = fmaxf(dynThrottle(throttle) * gyro.dynLpfMax, gyro.dynLpfMin);
} }
DEBUG_SET(DEBUG_DYN_LPF, 2, cutoffFreq); DEBUG_SET(DEBUG_DYN_LPF, 2, lrintf(cutoffFreq));
const float gyroDt = gyro.targetLooptime * 1e-6f; const float gyroDt = gyro.targetLooptime * 1e-6f;
switch (gyro.dynLpfFilter) { switch (gyro.dynLpfFilter) {
case DYN_LPF_PT1: case DYN_LPF_PT1:

View File

@ -72,7 +72,7 @@ extern "C" {
#include "unittest_macros.h" #include "unittest_macros.h"
#include "gtest/gtest.h" #include "gtest/gtest.h"
const float sqrt2over2 = sqrt(2) / 2.0f; const float sqrt2over2 = sqrtf(2) / 2.0f;
TEST(FlightImuTest, TestCalculateRotationMatrix) TEST(FlightImuTest, TestCalculateRotationMatrix)
{ {

View File

@ -207,8 +207,8 @@ TEST(MathsUnittest, TestFastTrigonometrySinCos)
{ {
double sinError = 0; double sinError = 0;
for (float x = -10 * M_PI; x < 10 * M_PI; x += M_PI / 300) { for (float x = -10 * M_PI; x < 10 * M_PI; x += M_PI / 300) {
double approxResult = sin_approx(x); float approxResult = sin_approx(x);
double libmResult = sinf(x); double libmResult = sin(x);
sinError = MAX(sinError, fabs(approxResult - libmResult)); sinError = MAX(sinError, fabs(approxResult - libmResult));
} }
printf("sin_approx maximum absolute error = %e\n", sinError); printf("sin_approx maximum absolute error = %e\n", sinError);
@ -216,8 +216,8 @@ TEST(MathsUnittest, TestFastTrigonometrySinCos)
double cosError = 0; double cosError = 0;
for (float x = -10 * M_PI; x < 10 * M_PI; x += M_PI / 300) { for (float x = -10 * M_PI; x < 10 * M_PI; x += M_PI / 300) {
double approxResult = cos_approx(x); float approxResult = cos_approx(x);
double libmResult = cosf(x); double libmResult = cos(x);
cosError = MAX(cosError, fabs(approxResult - libmResult)); cosError = MAX(cosError, fabs(approxResult - libmResult));
} }
printf("cos_approx maximum absolute error = %e\n", cosError); printf("cos_approx maximum absolute error = %e\n", cosError);
@ -229,8 +229,8 @@ TEST(MathsUnittest, TestFastTrigonometryATan2)
double error = 0; double error = 0;
for (float x = -1.0f; x < 1.0f; x += 0.01) { for (float x = -1.0f; x < 1.0f; x += 0.01) {
for (float y = -1.0f; x < 1.0f; x += 0.001) { for (float y = -1.0f; x < 1.0f; x += 0.001) {
double approxResult = atan2_approx(y, x); float approxResult = atan2_approx(y, x);
double libmResult = atan2f(y, x); double libmResult = atan2(y, x);
error = MAX(error, fabs(approxResult - libmResult)); error = MAX(error, fabs(approxResult - libmResult));
} }
} }
@ -242,7 +242,7 @@ TEST(MathsUnittest, TestFastTrigonometryACos)
{ {
double error = 0; double error = 0;
for (float x = -1.0f; x < 1.0f; x += 0.001) { for (float x = -1.0f; x < 1.0f; x += 0.001) {
double approxResult = acos_approx(x); float approxResult = acos_approx(x);
double libmResult = acos(x); double libmResult = acos(x);
error = MAX(error, fabs(approxResult - libmResult)); error = MAX(error, fabs(approxResult - libmResult));
} }

View File

@ -224,7 +224,7 @@ void setStickPosition(int axis, float stickRatio) {
// All calculations will have 10% tolerance // All calculations will have 10% tolerance
float calculateTolerance(float input) { float calculateTolerance(float input) {
return fabs(input * 0.1f); return fabsf(input * 0.1f);
} }
TEST(pidControllerTest, testInitialisation) TEST(pidControllerTest, testInitialisation)