1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00

Fixed some incorrect usages of FAST_CODE.

This commit is contained in:
mikeller 2019-11-24 14:07:35 +13:00
parent b137bbe80c
commit a6cf0e6f6c
4 changed files with 16 additions and 12 deletions

View file

@ -57,7 +57,7 @@ void dshotInitEndpoints(float outputLimit, float *outputLow, float *outputHigh,
float dshotConvertFromExternal(uint16_t externalValue); float dshotConvertFromExternal(uint16_t externalValue);
uint16_t dshotConvertToExternal(float motorValue); uint16_t dshotConvertToExternal(float motorValue);
FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb); uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb);
#ifdef USE_DSHOT_TELEMETRY #ifdef USE_DSHOT_TELEMETRY
extern bool useDshotTelemetry; extern bool useDshotTelemetry;

View file

@ -42,8 +42,8 @@
typedef uint8_t loadDmaBufferFn(uint32_t *dmaBuffer, int stride, uint16_t packet); // function pointer used to encode a digital motor value into the DMA buffer representation typedef uint8_t loadDmaBufferFn(uint32_t *dmaBuffer, int stride, uint16_t packet); // function pointer used to encode a digital motor value into the DMA buffer representation
extern FAST_RAM_ZERO_INIT loadDmaBufferFn *loadDmaBuffer; extern FAST_RAM_ZERO_INIT loadDmaBufferFn *loadDmaBuffer;
FAST_CODE uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet); uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet);
FAST_CODE uint8_t loadDmaBufferProshot(uint32_t *dmaBuffer, int stride, uint16_t packet); uint8_t loadDmaBufferProshot(uint32_t *dmaBuffer, int stride, uint16_t packet);
uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType); uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType);

View file

@ -60,8 +60,7 @@ motorDmaOutput_t *getMotorDmaOutput(uint8_t index);
void dshotEnableChannels(uint8_t motorCount); void dshotEnableChannels(uint8_t motorCount);
#ifdef USE_DSHOT_TELEMETRY #ifdef USE_DSHOT_TELEMETRY
void pwmDshotSetDirectionOutput(
FAST_CODE void pwmDshotSetDirectionOutput(
motorDmaOutput_t * const motor motorDmaOutput_t * const motor
#ifndef USE_DSHOT_TELEMETRY #ifndef USE_DSHOT_TELEMETRY
#if defined(STM32F7) || defined(STM32H7) #if defined(STM32F7) || defined(STM32H7)

View file

@ -30,11 +30,12 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "config/config.h"
#include "config/feature.h" #include "config/feature.h"
#include "config/config.h"
#include "fc/controlrate_profile.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "fc/controlrate_profile.h"
#include "fc/core.h" #include "fc/core.h"
#include "fc/rc.h" #include "fc/rc.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -45,12 +46,16 @@
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/gps_rescue.h" #include "flight/gps_rescue.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "pg/rx.h" #include "pg/rx.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "rc.h"
typedef float (applyRatesFn)(const int axis, float rcCommandf, const float rcCommandfAbs); typedef float (applyRatesFn)(const int axis, float rcCommandf, const float rcCommandfAbs);
#ifdef USE_INTERPOLATED_SP #ifdef USE_INTERPOLATED_SP
@ -272,7 +277,7 @@ static void checkForThrottleErrorResetState(uint16_t rxRefreshRate)
} }
} }
FAST_CODE uint8_t processRcInterpolation(void) static FAST_CODE uint8_t processRcInterpolation(void)
{ {
static FAST_RAM_ZERO_INIT float rcCommandInterp[4]; static FAST_RAM_ZERO_INIT float rcCommandInterp[4];
static FAST_RAM_ZERO_INIT float rcStepSize[4]; static FAST_RAM_ZERO_INIT float rcStepSize[4];
@ -351,7 +356,7 @@ FAST_CODE_NOINLINE int calcRcSmoothingCutoff(int avgRxFrameTimeUs, bool pt1, uin
// Preforms a reasonableness check on the rx frame time to avoid bad data // Preforms a reasonableness check on the rx frame time to avoid bad data
// skewing the average. // skewing the average.
FAST_CODE bool rcSmoothingRxRateValid(int currentRxRefreshRate) static FAST_CODE bool rcSmoothingRxRateValid(int currentRxRefreshRate)
{ {
return (currentRxRefreshRate >= RC_SMOOTHING_RX_RATE_MIN_US && currentRxRefreshRate <= RC_SMOOTHING_RX_RATE_MAX_US); return (currentRxRefreshRate >= RC_SMOOTHING_RX_RATE_MIN_US && currentRxRefreshRate <= RC_SMOOTHING_RX_RATE_MAX_US);
} }
@ -417,7 +422,7 @@ FAST_CODE_NOINLINE void rcSmoothingResetAccumulation(rcSmoothingFilter_t *smooth
// Accumulate the rx frame time samples. Once we've collected enough samples calculate the // Accumulate the rx frame time samples. Once we've collected enough samples calculate the
// average and return true. // average and return true.
FAST_CODE bool rcSmoothingAccumulateSample(rcSmoothingFilter_t *smoothingData, int rxFrameTimeUs) static FAST_CODE bool rcSmoothingAccumulateSample(rcSmoothingFilter_t *smoothingData, int rxFrameTimeUs)
{ {
smoothingData->training.sum += rxFrameTimeUs; smoothingData->training.sum += rxFrameTimeUs;
smoothingData->training.count++; smoothingData->training.count++;
@ -455,7 +460,7 @@ FAST_CODE_NOINLINE bool rcSmoothingAutoCalculate(void)
return ret; return ret;
} }
FAST_CODE uint8_t processRcSmoothingFilter(void) static FAST_CODE uint8_t processRcSmoothingFilter(void)
{ {
uint8_t updatedChannel = 0; uint8_t updatedChannel = 0;
static FAST_RAM_ZERO_INIT float lastRxData[4]; static FAST_RAM_ZERO_INIT float lastRxData[4];