Merge pull request #10711 from mikeller/remove_powerf

Remove unneeded library function 'powerf()'.
This commit is contained in:
Michael Keller 2021-04-28 01:28:43 +12:00 committed by GitHub
commit a53f2a60a5
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
7 changed files with 12 additions and 25 deletions

View File

@ -115,13 +115,6 @@ int gcd(int num, int denom)
return gcd(denom, num % denom);
}
float powerf(float base, int exp) {
float result = base;
for (int count = 1; count < exp; count++) result *= base;
return result;
}
int32_t applyDeadband(const int32_t value, const int32_t deadband)
{
if (ABS(value) < deadband) {

View File

@ -101,7 +101,6 @@ typedef struct fp_rotationMatrix_s {
} fp_rotationMatrix_t;
int gcd(int num, int denom);
float powerf(float base, int exp);
int32_t applyDeadband(int32_t value, int32_t deadband);
float fapplyDeadband(float value, float deadband);

View File

@ -38,7 +38,7 @@ static void applySqrt(const sdft_t *sdft, float *data);
void sdftInit(sdft_t *sdft, const uint8_t startBin, const uint8_t endBin, const uint8_t numBatches)
{
if (!isInitialized) {
rPowerN = powerf(SDFT_R, SDFT_SAMPLE_SIZE);
rPowerN = powf(SDFT_R, SDFT_SAMPLE_SIZE);
const float c = 2.0f * M_PIf / (float)SDFT_SAMPLE_SIZE;
float phi = 0.0f;
for (uint8_t i = 0; i < SDFT_BIN_COUNT; i++) {

View File

@ -20,28 +20,26 @@
* BMP388 Driver author: Dominic Clifton
*/
#include <math.h>
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "build/build_config.h"
#if defined(USE_BARO) && (defined(USE_BARO_BMP388) || defined(USE_BARO_SPI_BMP388))
#include "build/build_config.h"
#include "build/debug.h"
#include "common/maths.h"
#include "barometer.h"
#include "drivers/barometer/barometer.h"
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_busdev.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/time.h"
#include "drivers/nvic.h"
#include "drivers/time.h"
#include "barometer_bmp388.h"
@ -303,8 +301,8 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
// See datasheet 3.9.2 "Measurement rate in forced mode and normal mode"
baro->up_delay = 234 +
(392 + (powerf(2, BMP388_PRESSURE_OSR + 1) * 2000)) +
(313 + (powerf(2, BMP388_TEMPERATURE_OSR + 1) * 2000));
(392 + (powf(2, BMP388_PRESSURE_OSR + 1) * 2000)) +
(313 + (powf(2, BMP388_TEMPERATURE_OSR + 1) * 2000));
baro->calculate = bmp388Calculate;

View File

@ -27,7 +27,6 @@
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/utils.h"
#include "config/config.h"
@ -203,7 +202,7 @@ float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs
float applyActualRates(const int axis, float rcCommandf, const float rcCommandfAbs)
{
float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
expof = rcCommandfAbs * (powerf(rcCommandf, 5) * expof + rcCommandf * (1 - expof));
expof = rcCommandfAbs * (powf(rcCommandf, 5) * expof + rcCommandf * (1 - expof));
const float centerSensitivity = currentControlRateProfile->rcRates[axis] * 10.0f;
const float stickMovement = MAX(0, currentControlRateProfile->rates[axis] * 10.0f - centerSensitivity);

View File

@ -30,7 +30,6 @@
#include "common/axis.h"
#include "common/filter.h"
#include "common/maths.h"
#include "config/config_reset.h"
#include "config/simplified_tuning.h"
@ -321,7 +320,7 @@ float pidCompensateThrustLinearization(float throttle)
if (pidRuntime.thrustLinearization != 0.0f) {
// for whoops where a lot of TL is needed, allow more throttle boost
const float throttleReversed = (1.0f - throttle);
throttle /= 1.0f + pidRuntime.throttleCompensateAmount * powerf(throttleReversed, 2);
throttle /= 1.0f + pidRuntime.throttleCompensateAmount * powf(throttleReversed, 2);
}
return throttle;
}
@ -331,7 +330,7 @@ float pidApplyThrustLinearization(float motorOutput)
if (pidRuntime.thrustLinearization != 0.0f) {
if (motorOutput > 0.0f) {
const float motorOutputReversed = (1.0f - motorOutput);
motorOutput *= 1.0f + powerf(motorOutputReversed, 2) * pidRuntime.thrustLinearization;
motorOutput *= 1.0f + powf(motorOutputReversed, 2) * pidRuntime.thrustLinearization;
}
}
return motorOutput;

View File

@ -30,7 +30,6 @@
#include "common/axis.h"
#include "common/filter.h"
#include "common/maths.h"
#include "drivers/dshot_command.h"
@ -363,7 +362,7 @@ void pidInitConfig(const pidProfile_t *pidProfile)
#ifdef USE_THRUST_LINEARIZATION
pidRuntime.thrustLinearization = pidProfile->thrustLinearization / 100.0f;
pidRuntime.throttleCompensateAmount = pidRuntime.thrustLinearization - 0.5f * powerf(pidRuntime.thrustLinearization, 2);
pidRuntime.throttleCompensateAmount = pidRuntime.thrustLinearization - 0.5f * powf(pidRuntime.thrustLinearization, 2);
#endif
#if defined(USE_D_MIN)