1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

duplicate emptyline removal (#14027)

* trailing space removal

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* deduplicate empty lines

---------

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
This commit is contained in:
nerdCopter 2024-11-15 16:07:25 -06:00 committed by GitHub
parent 493b9bf819
commit ed6a4a4769
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
289 changed files with 0 additions and 629 deletions

View file

@ -91,7 +91,6 @@
#include "sensors/gyro_init.h" #include "sensors/gyro_init.h"
#include "sensors/rangefinder.h" #include "sensors/rangefinder.h"
#ifdef USE_FLASH_TEST_PRBS #ifdef USE_FLASH_TEST_PRBS
void checkFlashStart(void); void checkFlashStart(void);
void checkFlashStop(void); void checkFlashStop(void);
@ -337,7 +336,6 @@ typedef enum BlackboxState {
BLACKBOX_STATE_ERASED BLACKBOX_STATE_ERASED
} BlackboxState; } BlackboxState;
typedef struct blackboxMainState_s { typedef struct blackboxMainState_s {
uint32_t time; uint32_t time;

View file

@ -34,7 +34,6 @@
#include "common/encoding.h" #include "common/encoding.h"
#include "common/printf.h" #include "common/printf.h"
static void _putc(void *p, char c) static void _putc(void *p, char c)
{ {
(void)p; (void)p;
@ -46,7 +45,6 @@ static int blackboxPrintfv(const char *fmt, va_list va)
return tfp_format(NULL, _putc, fmt, va); return tfp_format(NULL, _putc, fmt, va);
} }
//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!) //printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!)
int blackboxPrintf(const char *fmt, ...) int blackboxPrintf(const char *fmt, ...)
{ {
@ -271,7 +269,6 @@ int blackboxWriteTag2_3SVariable(int32_t *values)
BYTES_4 = 3 BYTES_4 = 3
}; };
/* /*
* Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes * Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes
* below: * below:

View file

@ -322,7 +322,6 @@ bool blackboxDeviceOpen(void)
* = (looptime_ns * 3) / 500 * = (looptime_ns * 3) / 500
*/ */
switch (baudRateIndex) { switch (baudRateIndex) {
case BAUD_1000000: case BAUD_1000000:
case BAUD_1500000: case BAUD_1500000:

View file

@ -447,7 +447,6 @@ void cliPrintf(const char *format, ...)
va_end(va); va_end(va);
} }
void cliPrintLinef(const char *format, ...) void cliPrintLinef(const char *format, ...)
{ {
va_list va; va_list va;
@ -645,7 +644,6 @@ static void printValuePointer(const char *cmdName, const clivalue_t *var, const
} }
} }
static bool valuePtrEqualsDefault(const clivalue_t *var, const void *ptr, const void *ptrDefault) static bool valuePtrEqualsDefault(const clivalue_t *var, const void *ptr, const void *ptrDefault)
{ {
bool result = true; bool result = true;
@ -763,7 +761,6 @@ static uint8_t getRateProfileIndexToUse(void)
return rateProfileIndexToUse == CURRENT_PROFILE_INDEX ? getCurrentControlRateProfileIndex() : rateProfileIndexToUse; return rateProfileIndexToUse == CURRENT_PROFILE_INDEX ? getCurrentControlRateProfileIndex() : rateProfileIndexToUse;
} }
static uint16_t getValueOffset(const clivalue_t *value) static uint16_t getValueOffset(const clivalue_t *value)
{ {
switch (value->type & VALUE_SECTION_MASK) { switch (value->type & VALUE_SECTION_MASK) {
@ -1317,7 +1314,6 @@ static void cliSerial(const char *cmdName, char *cmdline)
serialPortConfig_t portConfig; serialPortConfig_t portConfig;
memset(&portConfig, 0 , sizeof(portConfig)); memset(&portConfig, 0 , sizeof(portConfig));
uint8_t validArgumentCount = 0; uint8_t validArgumentCount = 0;
const char *ptr = cmdline; const char *ptr = cmdline;
@ -1534,7 +1530,6 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
index++; index++;
} }
for (unsigned i = 0; i < ARRAYLEN(ports); i++) { for (unsigned i = 0; i < ARRAYLEN(ports); i++) {
if (findSerialPortIndexByIdentifier(ports[i].id) < 0) { if (findSerialPortIndexByIdentifier(ports[i].id) < 0) {
cliPrintLinef("Invalid port%d %d", i + 1, ports[i].id); cliPrintLinef("Invalid port%d %d", i + 1, ports[i].id);
@ -3530,7 +3525,6 @@ static void printMap(dumpFlags_t dumpMask, const rxConfig_t *rxConfig, const rxC
cliDumpPrintLinef(dumpMask, equalsDefault, formatMap, buf); cliDumpPrintLinef(dumpMask, equalsDefault, formatMap, buf);
} }
static void cliMap(const char *cmdName, char *cmdline) static void cliMap(const char *cmdName, char *cmdline)
{ {
uint32_t i; uint32_t i;
@ -3696,7 +3690,6 @@ static void cliDumpGyroRegisters(const char *cmdName, char *cmdline)
} }
#endif #endif
static int parseOutputIndex(const char *cmdName, char *pch, bool allowAllEscs) static int parseOutputIndex(const char *cmdName, char *pch, bool allowAllEscs)
{ {
int outputIndex = atoi(pch); int outputIndex = atoi(pch);
@ -6189,7 +6182,6 @@ static void cliResource(const char *cmdName, char *cmdline)
#ifdef USE_DSHOT_TELEMETRY #ifdef USE_DSHOT_TELEMETRY
static void cliDshotTelemetryInfo(const char *cmdName, char *cmdline) static void cliDshotTelemetryInfo(const char *cmdName, char *cmdline)
{ {
UNUSED(cmdName); UNUSED(cmdName);

View file

@ -137,7 +137,6 @@
#include "settings.h" #include "settings.h"
// Sensor names (used in lookup tables for *_hardware settings and in status command output) // Sensor names (used in lookup tables for *_hardware settings and in status command output)
// sync with accelerationSensor_e // sync with accelerationSensor_e
const char * const lookupTableAccHardware[] = { const char * const lookupTableAccHardware[] = {

View file

@ -24,7 +24,6 @@
#include <stdbool.h> #include <stdbool.h>
#include "pg/pg.h" #include "pg/pg.h"
typedef enum { typedef enum {
TABLE_OFF_ON = 0, TABLE_OFF_ON = 0,
TABLE_UNIT, TABLE_UNIT,
@ -158,7 +157,6 @@ typedef struct lookupTableEntry_s {
const uint8_t valueCount; const uint8_t valueCount;
} lookupTableEntry_t; } lookupTableEntry_t;
#define VALUE_TYPE_OFFSET 0 #define VALUE_TYPE_OFFSET 0
#define VALUE_SECTION_OFFSET 3 #define VALUE_SECTION_OFFSET 3
#define VALUE_MODE_OFFSET 5 #define VALUE_MODE_OFFSET 5
@ -186,7 +184,6 @@ typedef enum {
MODE_STRING = (4 << VALUE_MODE_OFFSET), MODE_STRING = (4 << VALUE_MODE_OFFSET),
} cliValueFlag_e; } cliValueFlag_e;
#define VALUE_TYPE_MASK (0x07) #define VALUE_TYPE_MASK (0x07)
#define VALUE_SECTION_MASK (0x18) #define VALUE_SECTION_MASK (0x18)
#define VALUE_MODE_MASK (0xE0) #define VALUE_MODE_MASK (0xE0)
@ -244,7 +241,6 @@ typedef struct clivalue_s {
uint16_t offset; uint16_t offset;
} PTR_PACKING clivalue_t; } PTR_PACKING clivalue_t;
extern const lookupTableEntry_t lookupTables[]; extern const lookupTableEntry_t lookupTables[];
extern const uint16_t valueTableEntryCount; extern const uint16_t valueTableEntryCount;

View file

@ -786,7 +786,6 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
} }
} }
// Highlight values overridden by sliders // Highlight values overridden by sliders
if (rowSliderOverride(p->flags)) { if (rowSliderOverride(p->flags)) {
displayWriteChar(pDisplay, leftMenuColumn - 1, top + i * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, 'S'); displayWriteChar(pDisplay, leftMenuColumn - 1, top + i * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, 'S');

View file

@ -220,7 +220,6 @@ static const void *cmsx_StorageDevice(displayPort_t *pDisplay, const void *ptr)
} }
#endif //USE_USB_MSC #endif //USE_USB_MSC
static const void *cmsx_Blackbox_onEnter(displayPort_t *pDisp) static const void *cmsx_Blackbox_onEnter(displayPort_t *pDisp)
{ {
UNUSED(pDisp); UNUSED(pDisp);

View file

@ -53,7 +53,6 @@
#include "cms_menu_firmware.h" #include "cms_menu_firmware.h"
// Calibration // Calibration
#define CALIBRATION_STATUS_MAX_LENGTH 6 #define CALIBRATION_STATUS_MAX_LENGTH 6

View file

@ -747,7 +747,6 @@ static CMS_Menu cmsx_menuProfileOther = {
.entries = cmsx_menuProfileOtherEntries, .entries = cmsx_menuProfileOtherEntries,
}; };
static uint16_t gyroConfig_gyro_lpf1_static_hz; static uint16_t gyroConfig_gyro_lpf1_static_hz;
static uint16_t gyroConfig_gyro_lpf2_static_hz; static uint16_t gyroConfig_gyro_lpf2_static_hz;
static uint16_t gyroConfig_gyro_soft_notch_hz_1; static uint16_t gyroConfig_gyro_soft_notch_hz_1;

View file

@ -129,7 +129,6 @@ static const void *cmsx_SaveExitMenu(displayPort_t *pDisplay, const void *ptr)
return NULL; return NULL;
} }
#ifdef USE_BATTERY_CONTINUE #ifdef USE_BATTERY_CONTINUE
#define SETUP_POPUP_MAX_ENTRIES 2 // Increase as new entries are added #define SETUP_POPUP_MAX_ENTRIES 2 // Increase as new entries are added
#else #else

View file

@ -20,7 +20,6 @@
#pragma once #pragma once
typedef enum { typedef enum {
RGB_RED = 0, RGB_RED = 0,
RGB_GREEN, RGB_GREEN,

View file

@ -26,7 +26,6 @@
#include "streambuf.h" #include "streambuf.h"
uint16_t crc16_ccitt(uint16_t crc, unsigned char a) uint16_t crc16_ccitt(uint16_t crc, unsigned char a)
{ {
crc ^= (uint16_t)a << 8; crc ^= (uint16_t)a << 8;

View file

@ -82,7 +82,6 @@ float log_approx(float val)
valu.i = (valu.i & 0x7FFFFF) | 0x3F800000; valu.i = (valu.i & 0x7FFFFF) | 0x3F800000;
x = valu.f; x = valu.f;
/* Generated in Sollya using: /* Generated in Sollya using:
> f = remez(log(x)-(x-1)*log(2), > f = remez(log(x)-(x-1)*log(2),
[|1,(x-1)*(x-2), (x-1)*(x-2)*x, (x-1)*(x-2)*x*x, [|1,(x-1)*(x-2), (x-1)*(x-2)*x, (x-1)*(x-2)*x*x,

View file

@ -42,7 +42,6 @@ float nullFilterApply(filter_t *filter, float input)
return input; return input;
} }
// PT1 Low Pass filter // PT1 Low Pass filter
FAST_CODE_NOINLINE float pt1FilterGain(float f_cut, float dT) FAST_CODE_NOINLINE float pt1FilterGain(float f_cut, float dT)
@ -79,7 +78,6 @@ FAST_CODE float pt1FilterApply(pt1Filter_t *filter, float input)
return filter->state; return filter->state;
} }
// PT2 Low Pass filter // PT2 Low Pass filter
FAST_CODE float pt2FilterGain(float f_cut, float dT) FAST_CODE float pt2FilterGain(float f_cut, float dT)
@ -118,7 +116,6 @@ FAST_CODE float pt2FilterApply(pt2Filter_t *filter, float input)
return filter->state; return filter->state;
} }
// PT3 Low Pass filter // PT3 Low Pass filter
FAST_CODE float pt3FilterGain(float f_cut, float dT) FAST_CODE float pt3FilterGain(float f_cut, float dT)
@ -159,7 +156,6 @@ FAST_CODE float pt3FilterApply(pt3Filter_t *filter, float input)
return filter->state; return filter->state;
} }
// Biquad filter // Biquad filter
// get notch filter Q given center frequency (f0) and lower cutoff frequency (f1) // get notch filter Q given center frequency (f0) and lower cutoff frequency (f1)
@ -274,7 +270,6 @@ FAST_CODE float biquadFilterApply(biquadFilter_t *filter, float input)
return result; return result;
} }
// Phase Compensator (Lead-Lag-Compensator) // Phase Compensator (Lead-Lag-Compensator)
void phaseCompInit(phaseComp_t *filter, const float centerFreqHz, const float centerPhaseDeg, const uint32_t looptimeUs) void phaseCompInit(phaseComp_t *filter, const float centerFreqHz, const float centerPhaseDeg, const uint32_t looptimeUs)
@ -315,7 +310,6 @@ FAST_CODE float phaseCompApply(phaseComp_t *filter, const float input)
return result; return result;
} }
// Slew filter with limit // Slew filter with limit
void slewFilterInit(slewFilter_t *filter, float slewLimit, float threshold) void slewFilterInit(slewFilter_t *filter, float slewLimit, float threshold)
@ -341,7 +335,6 @@ FAST_CODE float slewFilterApply(slewFilter_t *filter, float input)
return filter->state; return filter->state;
} }
// Moving average // Moving average
void laggedMovingAverageInit(laggedMovingAverage_t *filter, uint16_t windowSize, float *buf) void laggedMovingAverageInit(laggedMovingAverage_t *filter, uint16_t windowSize, float *buf)
@ -369,7 +362,6 @@ FAST_CODE float laggedMovingAverageUpdate(laggedMovingAverage_t *filter, float i
return filter->movingSum / denom; return filter->movingSum / denom;
} }
// Simple fixed-point lowpass filter based on integer math // Simple fixed-point lowpass filter based on integer math
void simpleLPFilterInit(simpleLowpassFilter_t *filter, int32_t beta, int32_t fpShift) void simpleLPFilterInit(simpleLowpassFilter_t *filter, int32_t beta, int32_t fpShift)
@ -388,7 +380,6 @@ int32_t simpleLPFilterUpdate(simpleLowpassFilter_t *filter, int32_t newVal)
return result; return result;
} }
// Mean accumulator // Mean accumulator
void meanAccumulatorInit(meanAccumulator_t *filter) void meanAccumulatorInit(meanAccumulator_t *filter)

View file

@ -27,7 +27,6 @@
#ifdef USE_GPS #ifdef USE_GPS
#define DIGIT_TO_VAL(_x) (_x - '0') #define DIGIT_TO_VAL(_x) (_x - '0')
uint32_t GPS_coord_to_degrees(const char* coordinateString) uint32_t GPS_coord_to_degrees(const char* coordinateString)
{ {

View file

@ -24,7 +24,6 @@
#include "huffman.h" #include "huffman.h"
int huffmanEncodeBuf(uint8_t *outBuf, int outBufLen, const uint8_t *inBuf, int inLen, const huffmanTable_t *huffmanTable) int huffmanEncodeBuf(uint8_t *outBuf, int outBufLen, const uint8_t *inBuf, int inLen, const huffmanTable_t *huffmanTable)
{ {
int ret = 0; int ret = 0;

View file

@ -43,7 +43,6 @@
#define DEGREES_TO_RADIANS(angle) ((angle) * RAD) #define DEGREES_TO_RADIANS(angle) ((angle) * RAD)
#define RADIANS_TO_DEGREES(angle) ((angle) / RAD) #define RADIANS_TO_DEGREES(angle) ((angle) / RAD)
#define CM_S_TO_KM_H(centimetersPerSecond) ((centimetersPerSecond) * 36 / 1000) #define CM_S_TO_KM_H(centimetersPerSecond) ((centimetersPerSecond) * 36 / 1000)
#define CM_S_TO_MPH(centimetersPerSecond) ((centimetersPerSecond) * 10000 / 5080 / 88) #define CM_S_TO_MPH(centimetersPerSecond) ((centimetersPerSecond) * 10000 / 5080 / 88)

View file

@ -44,7 +44,6 @@
#include "typeconversion.h" #include "typeconversion.h"
#endif #endif
#ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT #ifdef REQUIRE_CC_ARM_PRINTF_SUPPORT
putcf stdout_putf; putcf stdout_putf;

View file

@ -18,7 +18,6 @@
* If not, see <http://www.gnu.org/licenses/>. * If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>
@ -60,7 +59,6 @@ static void _putc(void *p, char c)
serialWrite(printfSerialPort, c); serialWrite(printfSerialPort, c);
} }
void printfSerialInit(void) void printfSerialInit(void)
{ {
init_printf(NULL, _putc); init_printf(NULL, _putc);

View file

@ -18,7 +18,6 @@
* If not, see <http://www.gnu.org/licenses/>. * If not, see <http://www.gnu.org/licenses/>.
*/ */
struct serialPort_s; struct serialPort_s;
void printfSerialInit(void); void printfSerialInit(void);

View file

@ -23,7 +23,6 @@
#include "pwl.h" #include "pwl.h"
void pwlInitialize(pwl_t *pwl, float *yValues, int numPoints, float xMin, float xMax) { void pwlInitialize(pwl_t *pwl, float *yValues, int numPoints, float xMin, float xMax) {
pwl->yValues = yValues; pwl->yValues = yValues;
pwl->numPoints = numPoints; pwl->numPoints = numPoints;

View file

@ -23,7 +23,6 @@
#include "utils.h" #include "utils.h"
#define PWL_DECLARE(name, size, xMinV, xMaxV) \ #define PWL_DECLARE(name, size, xMinV, xMaxV) \
STATIC_ASSERT((xMinV) < (xMaxV), "xMinV must be less than xMaxV"); \ STATIC_ASSERT((xMinV) < (xMaxV), "xMinV must be less than xMaxV"); \
STATIC_ASSERT((size) > 1, "size must be more than 1"); \ STATIC_ASSERT((size) > 1, "size must be more than 1"); \

View file

@ -35,7 +35,6 @@ static FAST_DATA_ZERO_INIT complex_t twiddle[SDFT_BIN_COUNT];
static void applySqrt(const sdft_t *sdft, float *data); static void applySqrt(const sdft_t *sdft, float *data);
static void updateEdges(sdft_t *sdft, const float value, const int batchIdx); static void updateEdges(sdft_t *sdft, const float value, const int batchIdx);
void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numBatches) void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numBatches)
{ {
if (!isInitialized) { if (!isInitialized) {
@ -65,7 +64,6 @@ void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numB
} }
} }
// Add new sample to frequency spectrum // Add new sample to frequency spectrum
FAST_CODE void sdftPush(sdft_t *sdft, const float sample) FAST_CODE void sdftPush(sdft_t *sdft, const float sample)
{ {
@ -81,7 +79,6 @@ FAST_CODE void sdftPush(sdft_t *sdft, const float sample)
updateEdges(sdft, delta, 0); updateEdges(sdft, delta, 0);
} }
// Add new sample to frequency spectrum in parts // Add new sample to frequency spectrum in parts
FAST_CODE void sdftPushBatch(sdft_t *sdft, const float sample, const int batchIdx) FAST_CODE void sdftPushBatch(sdft_t *sdft, const float sample, const int batchIdx)
{ {
@ -105,7 +102,6 @@ FAST_CODE void sdftPushBatch(sdft_t *sdft, const float sample, const int batchId
updateEdges(sdft, delta, batchIdx); updateEdges(sdft, delta, batchIdx);
} }
// Get squared magnitude of frequency spectrum // Get squared magnitude of frequency spectrum
FAST_CODE void sdftMagSq(const sdft_t *sdft, float *output) FAST_CODE void sdftMagSq(const sdft_t *sdft, float *output)
{ {
@ -119,7 +115,6 @@ FAST_CODE void sdftMagSq(const sdft_t *sdft, float *output)
} }
} }
// Get magnitude of frequency spectrum (slower) // Get magnitude of frequency spectrum (slower)
FAST_CODE void sdftMagnitude(const sdft_t *sdft, float *output) FAST_CODE void sdftMagnitude(const sdft_t *sdft, float *output)
{ {
@ -127,7 +122,6 @@ FAST_CODE void sdftMagnitude(const sdft_t *sdft, float *output)
applySqrt(sdft, output); applySqrt(sdft, output);
} }
// Get squared magnitude of frequency spectrum with Hann window applied // Get squared magnitude of frequency spectrum with Hann window applied
// Hann window in frequency domain: X[k] = -0.25 * X[k-1] +0.5 * X[k] -0.25 * X[k+1] // Hann window in frequency domain: X[k] = -0.25 * X[k-1] +0.5 * X[k] -0.25 * X[k+1]
FAST_CODE void sdftWinSq(const sdft_t *sdft, float *output) FAST_CODE void sdftWinSq(const sdft_t *sdft, float *output)
@ -164,7 +158,6 @@ FAST_CODE void sdftWinSq(const sdft_t *sdft, float *output)
output[sdft->endBin] = re * re + im * im; output[sdft->endBin] = re * re + im * im;
} }
// Get magnitude of frequency spectrum with Hann window applied (slower) // Get magnitude of frequency spectrum with Hann window applied (slower)
FAST_CODE void sdftWindow(const sdft_t *sdft, float *output) FAST_CODE void sdftWindow(const sdft_t *sdft, float *output)
{ {
@ -172,7 +165,6 @@ FAST_CODE void sdftWindow(const sdft_t *sdft, float *output)
applySqrt(sdft, output); applySqrt(sdft, output);
} }
// Apply square root to the whole sdft range // Apply square root to the whole sdft range
static FAST_CODE void applySqrt(const sdft_t *sdft, float *data) static FAST_CODE void applySqrt(const sdft_t *sdft, float *data)
{ {
@ -181,7 +173,6 @@ static FAST_CODE void applySqrt(const sdft_t *sdft, float *data)
} }
} }
// Needed for proper windowing at the edges of active range // Needed for proper windowing at the edges of active range
static FAST_CODE void updateEdges(sdft_t *sdft, const float value, const int batchIdx) static FAST_CODE void updateEdges(sdft_t *sdft, const float value, const int batchIdx)
{ {

View file

@ -39,7 +39,6 @@ void buildRotationMatrixFromAngles(matrix33_t *rm, const sensorAlignment_t *rpy)
buildRotationMatrix(rm, &rotationAngles); buildRotationMatrix(rm, &rotationAngles);
} }
void buildAlignmentFromStandardAlignment(sensorAlignment_t* rpy, sensor_align_e stdAlignment) void buildAlignmentFromStandardAlignment(sensorAlignment_t* rpy, sensor_align_e stdAlignment)
{ {
if (stdAlignment == ALIGN_CUSTOM || stdAlignment == ALIGN_DEFAULT) { if (stdAlignment == ALIGN_CUSTOM || stdAlignment == ALIGN_DEFAULT) {

View file

@ -65,7 +65,6 @@ void sbufWriteU32BigEndian(sbuf_t *dst, uint32_t val)
sbufWriteU8(dst, (uint8_t)val); sbufWriteU8(dst, (uint8_t)val);
} }
void sbufFill(sbuf_t *dst, uint8_t data, int len) void sbufFill(sbuf_t *dst, uint8_t data, int len)
{ {
memset(dst->ptr, data, len); memset(dst->ptr, data, len);

View file

@ -19,7 +19,6 @@
*/ */
#include <ctype.h> #include <ctype.h>
#include <limits.h> #include <limits.h>

View file

@ -79,8 +79,6 @@ static inline int popcount(unsigned x) { return __builtin_popcount(x); }
static inline int popcount32(uint32_t x) { return __builtin_popcount(x); } static inline int popcount32(uint32_t x) { return __builtin_popcount(x); }
static inline int popcount64(uint64_t x) { return __builtin_popcountll(x); } static inline int popcount64(uint64_t x) { return __builtin_popcountll(x); }
/* /*
* https://groups.google.com/forum/?hl=en#!msg/comp.lang.c/attFnqwhvGk/sGBKXvIkY3AJ * https://groups.google.com/forum/?hl=en#!msg/comp.lang.c/attFnqwhvGk/sGBKXvIkY3AJ
* Return (v ? floor(log2(v)) : 0) when 0 <= v < 1<<[8, 16, 32, 64]. * Return (v ? floor(log2(v)) : 0) when 0 <= v < 1<<[8, 16, 32, 64].
@ -121,7 +119,6 @@ static inline void memcpy_fn ( void * destination, const void * source, size_t
void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("memcpy"); void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("memcpy");
#endif #endif
#endif #endif
#if __GNUC__ > 6 #if __GNUC__ > 6

View file

@ -153,7 +153,6 @@ MMFLASH_CODE_NOINLINE void saveEEPROMToMemoryMappedFlash(void)
} }
#endif #endif
#elif defined(CONFIG_IN_SDCARD) #elif defined(CONFIG_IN_SDCARD)
enum { enum {
@ -477,7 +476,6 @@ static bool writeSettingsToEEPROM(void)
.flags = 0, .flags = 0,
}; };
record.flags |= CR_CLASSICATION_SYSTEM; record.flags |= CR_CLASSICATION_SYSTEM;
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record)); config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
crc = crc16_ccitt_update(crc, (uint8_t *)&record, sizeof(record)); crc = crc16_ccitt_update(crc, (uint8_t *)&record, sizeof(record));

View file

@ -36,7 +36,6 @@ uint8_t eepromData[EEPROM_SIZE];
#endif #endif
#endif #endif
#if !defined(FLASH_PAGE_SIZE) #if !defined(FLASH_PAGE_SIZE)
#error "Flash page size not defined for target." #error "Flash page size not defined for target."
#endif #endif

View file

@ -28,7 +28,6 @@
#include "pg/pg.h" #include "pg/pg.h"
#include "pg/pg_ids.h" #include "pg/pg_ids.h"
PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 1); PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 1);
PG_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_RESET_TEMPLATE(featureConfig_t, featureConfig,

View file

@ -115,7 +115,6 @@ void applySimplifiedTuningGyroFilters(gyroConfig_t *gyroConfig)
} }
} }
void applySimplifiedTuning(pidProfile_t *pidProfile, gyroConfig_t *gyroConfig) void applySimplifiedTuning(pidProfile_t *pidProfile, gyroConfig_t *gyroConfig)
{ {
applySimplifiedTuningPids(pidProfile); applySimplifiedTuningPids(pidProfile);

View file

@ -214,7 +214,6 @@ bool mpuGyroRead(gyroDev_t *gyro)
return true; return true;
} }
#ifdef USE_SPI_GYRO #ifdef USE_SPI_GYRO
bool mpuAccReadSPI(accDev_t *acc) bool mpuAccReadSPI(accDev_t *acc)
{ {

View file

@ -364,7 +364,6 @@ static bool bmi160AccRead(accDev_t *acc)
return true; return true;
} }
static bool bmi160GyroRead(gyroDev_t *gyro) static bool bmi160GyroRead(gyroDev_t *gyro)
{ {
extDevice_t *dev = &gyro->dev; extDevice_t *dev = &gyro->dev;
@ -438,7 +437,6 @@ static bool bmi160GyroRead(gyroDev_t *gyro)
return true; return true;
} }
void bmi160SpiGyroInit(gyroDev_t *gyro) void bmi160SpiGyroInit(gyroDev_t *gyro)
{ {
extDevice_t *dev = &gyro->dev; extDevice_t *dev = &gyro->dev;
@ -454,7 +452,6 @@ void bmi160SpiAccInit(accDev_t *acc)
acc->acc_1G = 512 * 8; acc->acc_1G = 512 * 8;
} }
bool bmi160SpiAccDetect(accDev_t *acc) bool bmi160SpiAccDetect(accDev_t *acc)
{ {
if (acc->mpuDetectionResult.sensor != BMI_160_SPI) { if (acc->mpuDetectionResult.sensor != BMI_160_SPI) {
@ -467,7 +464,6 @@ bool bmi160SpiAccDetect(accDev_t *acc)
return true; return true;
} }
bool bmi160SpiGyroDetect(gyroDev_t *gyro) bool bmi160SpiGyroDetect(gyroDev_t *gyro)
{ {
if (gyro->mpuDetectionResult.sensor != BMI_160_SPI) { if (gyro->mpuDetectionResult.sensor != BMI_160_SPI) {

View file

@ -555,7 +555,6 @@ bool bmi270SpiAccDetect(accDev_t *acc)
return true; return true;
} }
bool bmi270SpiGyroDetect(gyroDev_t *gyro) bool bmi270SpiGyroDetect(gyroDev_t *gyro)
{ {
if (gyro->mpuDetectionResult.sensor != BMI_270_SPI) { if (gyro->mpuDetectionResult.sensor != BMI_270_SPI) {

View file

@ -38,7 +38,6 @@
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/time.h" #include "drivers/time.h"
// 8 MHz max SPI frequency // 8 MHz max SPI frequency
#define ICM20649_MAX_SPI_CLK_HZ 8000000 #define ICM20649_MAX_SPI_CLK_HZ 8000000
@ -98,7 +97,6 @@ bool icm20649SpiAccDetect(accDev_t *acc)
return true; return true;
} }
void icm20649GyroInit(gyroDev_t *gyro) void icm20649GyroInit(gyroDev_t *gyro)
{ {
mpuGyroInit(gyro); mpuGyroInit(gyro);

View file

@ -373,7 +373,6 @@ void icm426xxGyroInit(gyroDev_t *gyro)
intfConfig1Value |= ICM426XX_INTF_CONFIG1_AFSR_DISABLE; intfConfig1Value |= ICM426XX_INTF_CONFIG1_AFSR_DISABLE;
spiWriteReg(dev, ICM426XX_INTF_CONFIG1, intfConfig1Value); spiWriteReg(dev, ICM426XX_INTF_CONFIG1, intfConfig1Value);
// Turn on gyro and acc on again so ODR and FSR can be configured // Turn on gyro and acc on again so ODR and FSR can be configured
turnGyroAccOn(dev); turnGyroAccOn(dev);

View file

@ -289,7 +289,6 @@
#define LSM6DSV_CTRL2_ODR_G_3200HZ 11 #define LSM6DSV_CTRL2_ODR_G_3200HZ 11
#define LSM6DSV_CTRL2_ODR_G_6400HZ 12 #define LSM6DSV_CTRL2_ODR_G_6400HZ 12
// Control register 3 (R/W) // Control register 3 (R/W)
#define LSM6DSV_CTRL3 0x12 #define LSM6DSV_CTRL3 0x12
#define LSM6DSV_CTRL3_BOOT 0x80 #define LSM6DSV_CTRL3_BOOT 0x80
@ -846,7 +845,6 @@
#define LSM6DSV_FIFO_DATA_OUT_Z_L 0x7D #define LSM6DSV_FIFO_DATA_OUT_Z_L 0x7D
#define LSM6DSV_FIFO_DATA_OUT_Z_H 0x7E #define LSM6DSV_FIFO_DATA_OUT_Z_H 0x7E
uint8_t lsm6dsv16xSpiDetect(const extDevice_t *dev) uint8_t lsm6dsv16xSpiDetect(const extDevice_t *dev)
{ {
const uint8_t whoAmI = spiReadRegMsk(dev, LSM6DSV_WHO_AM_I); const uint8_t whoAmI = spiReadRegMsk(dev, LSM6DSV_WHO_AM_I);

View file

@ -44,7 +44,6 @@
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/system.h" #include "drivers/system.h"
static void mpu6000AccAndGyroInit(gyroDev_t *gyro); static void mpu6000AccAndGyroInit(gyroDev_t *gyro);
// 20 MHz max SPI frequency // 20 MHz max SPI frequency

View file

@ -49,7 +49,6 @@
static void mpu9250AccAndGyroInit(gyroDev_t *gyro); static void mpu9250AccAndGyroInit(gyroDev_t *gyro);
bool mpu9250SpiWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data) bool mpu9250SpiWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data)
{ {
delayMicroseconds(1); delayMicroseconds(1);

View file

@ -102,7 +102,6 @@ bool virtualGyroDetect(gyroDev_t *gyro)
} }
#endif // USE_VIRTUAL_GYRO #endif // USE_VIRTUAL_GYRO
#ifdef USE_VIRTUAL_ACC #ifdef USE_VIRTUAL_ACC
static int16_t virtualAccData[XYZ_AXIS_COUNT]; static int16_t virtualAccData[XYZ_AXIS_COUNT];

View file

@ -34,7 +34,6 @@
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/gyro_sync.h" #include "drivers/accgyro/gyro_sync.h"
bool gyroSyncCheckUpdate(gyroDev_t *gyro) bool gyroSyncCheckUpdate(gyroDev_t *gyro)
{ {
bool ret; bool ret;

View file

@ -38,7 +38,6 @@
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/system.h" #include "drivers/system.h"
// L3G4200D, Standard address 0x68 // L3G4200D, Standard address 0x68
#define L3G4200D_ADDRESS 0x68 #define L3G4200D_ADDRESS 0x68
#define L3G4200D_ID 0xD3 #define L3G4200D_ID 0xD3

View file

@ -431,5 +431,4 @@ typedef struct {
#define LSM303DLHC_TEMPSENSOR_ENABLE ((uint8_t) 0x80) /*!< Temp sensor Enable */ #define LSM303DLHC_TEMPSENSOR_ENABLE ((uint8_t) 0x80) /*!< Temp sensor Enable */
#define LSM303DLHC_TEMPSENSOR_DISABLE ((uint8_t) 0x00) /*!< Temp sensor Disable */ #define LSM303DLHC_TEMPSENSOR_DISABLE ((uint8_t) 0x00) /*!< Temp sensor Disable */
bool lsm303dlhcAccDetect(accDev_t *acc); bool lsm303dlhcAccDetect(accDev_t *acc);

View file

@ -99,7 +99,6 @@ typedef struct {
static baroState_t baroState; static baroState_t baroState;
static uint8_t baroDataBuf[6]; static uint8_t baroDataBuf[6];
static int32_t readSignedRegister(const extDevice_t *dev, uint8_t reg, uint8_t nBytes) static int32_t readSignedRegister(const extDevice_t *dev, uint8_t reg, uint8_t nBytes)
{ {
uint8_t buf[3]; uint8_t buf[3];

View file

@ -42,7 +42,6 @@
#if defined(USE_BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)) #if defined(USE_BARO) && (defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280))
#define BMP280_I2C_ADDR (0x76) #define BMP280_I2C_ADDR (0x76)
#define BMP280_DEFAULT_CHIP_ID (0x58) #define BMP280_DEFAULT_CHIP_ID (0x58)
#define BME280_DEFAULT_CHIP_ID (0x60) #define BME280_DEFAULT_CHIP_ID (0x60)

View file

@ -183,7 +183,6 @@ static bool bmp388ReadUP(baroDev_t *baro);
STATIC_UNIT_TESTED void bmp388Calculate(int32_t *pressure, int32_t *temperature); STATIC_UNIT_TESTED void bmp388Calculate(int32_t *pressure, int32_t *temperature);
static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length) static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length)
{ {
if (dev->bus->busType == BUS_TYPE_SPI) { if (dev->bus->busType == BUS_TYPE_SPI) {
@ -297,7 +296,6 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
// read calibration // read calibration
bmp388ReadRegisterBuffer(dev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t *)&bmp388_cal, sizeof(bmp388_calib_param_t)); bmp388ReadRegisterBuffer(dev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t *)&bmp388_cal, sizeof(bmp388_calib_param_t));
// set oversampling // set oversampling
busWriteRegister(dev, BMP388_OSR_REG, busWriteRegister(dev, BMP388_OSR_REG,
((BMP388_PRESSURE_OSR << BMP388_OSR_P_BIT) & BMP388_OSR_P_MASK) | ((BMP388_PRESSURE_OSR << BMP388_OSR_P_BIT) & BMP388_OSR_P_MASK) |

View file

@ -314,8 +314,6 @@ static void deviceCalculate(int32_t *pressure, int32_t *temperature)
} }
} }
#define DETECTION_MAX_RETRY_COUNT 5 #define DETECTION_MAX_RETRY_COUNT 5
static bool deviceDetect(const extDevice_t *dev) static bool deviceDetect(const extDevice_t *dev)
{ {

View file

@ -217,7 +217,6 @@ STATIC_UNIT_TESTED void ms5611Calculate(int32_t *pressure, int32_t *temperature)
} }
press = ((((int64_t)ms5611_up * sens) >> 21) - off) >> 15; press = ((((int64_t)ms5611_up * sens) >> 21) - off) >> 15;
if (pressure) if (pressure)
*pressure = press; *pressure = press;
if (temperature) if (temperature)

View file

@ -342,8 +342,6 @@ static float qmp6988CompensateTemperature(int32_t adc_T)
return T; return T;
} }
STATIC_UNIT_TESTED void qmp6988Calculate(int32_t *pressure, int32_t *temperature) STATIC_UNIT_TESTED void qmp6988Calculate(int32_t *pressure, int32_t *temperature)
{ {
float tr,pr; float tr,pr;

View file

@ -30,11 +30,9 @@
#include "barometer.h" #include "barometer.h"
#include "barometer_virtual.h" #include "barometer_virtual.h"
static int32_t virtualPressure; static int32_t virtualPressure;
static int32_t virtualTemperature; static int32_t virtualTemperature;
static bool virtualBaroStart(baroDev_t *baro) static bool virtualBaroStart(baroDev_t *baro)
{ {
UNUSED(baro); UNUSED(baro);

View file

@ -27,7 +27,6 @@
#include "drivers/bus_i2c_busdev.h" #include "drivers/bus_i2c_busdev.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
// Access routines where the register is accessed directly // Access routines where the register is accessed directly
bool busRawWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data) bool busRawWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data)
{ {
@ -77,7 +76,6 @@ bool busRawReadRegisterBufferStart(const extDevice_t *dev, uint8_t reg, uint8_t
} }
} }
// Write routines where the register is masked with 0x7f // Write routines where the register is masked with 0x7f
bool busWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data) bool busWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data)
{ {

View file

@ -42,7 +42,6 @@ typedef enum OCTOSPIDevice {
OCTOSPIDevice octoSpiDeviceByInstance(OCTOSPI_TypeDef *instance); OCTOSPIDevice octoSpiDeviceByInstance(OCTOSPI_TypeDef *instance);
OCTOSPI_TypeDef *octoSpiInstanceByDevice(OCTOSPIDevice device); OCTOSPI_TypeDef *octoSpiInstanceByDevice(OCTOSPIDevice device);
bool octoSpiInit(OCTOSPIDevice device); bool octoSpiInit(OCTOSPIDevice device);
bool octoSpiReceive1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length); bool octoSpiReceive1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length);
bool octoSpiReceive4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length); bool octoSpiReceive4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length);
@ -55,7 +54,6 @@ bool octoSpiTransmitWithAddress4LINES(OCTOSPI_TypeDef *instance, uint8_t instruc
bool octoSpiInstructionWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize); bool octoSpiInstructionWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize);
void octoSpiDisableMemoryMappedMode(OCTOSPI_TypeDef *instance); void octoSpiDisableMemoryMappedMode(OCTOSPI_TypeDef *instance);
void octoSpiEnableMemoryMappedMode(OCTOSPI_TypeDef *instance); void octoSpiEnableMemoryMappedMode(OCTOSPI_TypeDef *instance);

View file

@ -262,7 +262,6 @@ void quadSpiPinConfigure(const quadSpiConfig_t *pConfig)
haveResources = haveResources && pDev->bk2CS; haveResources = haveResources && pDev->bk2CS;
} }
if (haveResources) { if (haveResources) {
pDev->dev = hw->reg; pDev->dev = hw->reg;
pDev->rcc = hw->rcc; pDev->rcc = hw->rcc;

View file

@ -101,7 +101,6 @@ typedef enum {
// Hardware does NOT support using BK1_NCS for single flash chip on BK2. // Hardware does NOT support using BK1_NCS for single flash chip on BK2.
// It's possible to use BK1_NCS for single chip on BK2 using software CS via QUADSPI_BK2_CS_SOFTWARE // It's possible to use BK1_NCS for single chip on BK2 using software CS via QUADSPI_BK2_CS_SOFTWARE
void quadSpiPreInit(void); void quadSpiPreInit(void);
bool quadSpiInit(QUADSPIDevice device); bool quadSpiInit(QUADSPIDevice device);
@ -118,7 +117,6 @@ bool quadSpiReceiveWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruct
bool quadSpiTransmitWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length); bool quadSpiTransmitWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length);
bool quadSpiTransmitWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length); bool quadSpiTransmitWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length);
bool quadSpiInstructionWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize); bool quadSpiInstructionWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize);
//bool quadSpiIsBusBusy(SPI_TypeDef *instance); //bool quadSpiIsBusBusy(SPI_TypeDef *instance);

View file

@ -22,7 +22,6 @@
#pragma once #pragma once
typedef struct quadSpiPinDef_s { typedef struct quadSpiPinDef_s {
ioTag_t pin; ioTag_t pin;
#if defined(STM32H7) #if defined(STM32H7)

View file

@ -107,7 +107,6 @@ bool spiInit(SPIDevice device);
// Called after all devices are initialised to enable SPI DMA where streams are available. // Called after all devices are initialised to enable SPI DMA where streams are available.
void spiInitBusDMA(); void spiInitBusDMA();
SPIDevice spiDeviceByInstance(const SPI_TypeDef *instance); SPIDevice spiDeviceByInstance(const SPI_TypeDef *instance);
SPI_TypeDef *spiInstanceByDevice(SPIDevice device); SPI_TypeDef *spiInstanceByDevice(SPIDevice device);

View file

@ -33,7 +33,6 @@
#include "compass.h" #include "compass.h"
#include "compass_virtual.h" #include "compass_virtual.h"
static int16_t virtualMagData[XYZ_AXIS_COUNT]; static int16_t virtualMagData[XYZ_AXIS_COUNT];
static bool virtualMagInit(magDev_t *mag) static bool virtualMagInit(magDev_t *mag)

View file

@ -102,7 +102,6 @@ typedef struct displayCanvasVTable_s {
void (*contextPop)(displayCanvas_t *displayCanvas); void (*contextPop)(displayCanvas_t *displayCanvas);
} displayCanvasVTable_t; } displayCanvasVTable_t;
void displayCanvasSetStrokeColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); void displayCanvasSetStrokeColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color);
void displayCanvasSetFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); void displayCanvasSetFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color);
void displayCanvasSetStrokeAndFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); void displayCanvasSetStrokeAndFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color);

View file

@ -135,7 +135,6 @@ typedef enum {
#define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift) #define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift)
#define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift)) #define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift))
#define DMA_IT_TCIF ((uint32_t)0x00000020) #define DMA_IT_TCIF ((uint32_t)0x00000020)
#define DMA_IT_HTIF ((uint32_t)0x00000010) #define DMA_IT_HTIF ((uint32_t)0x00000010)
#define DMA_IT_TEIF ((uint32_t)0x00000008) #define DMA_IT_TEIF ((uint32_t)0x00000008)

View file

@ -100,7 +100,6 @@ typedef struct dshotTelemetryMotorState_s {
uint8_t maxTemp; uint8_t maxTemp;
} dshotTelemetryMotorState_t; } dshotTelemetryMotorState_t;
typedef struct dshotTelemetryState_s { typedef struct dshotTelemetryState_s {
bool useDshotTelemetry; bool useDshotTelemetry;
uint32_t invalidPacketCount; uint32_t invalidPacketCount;

View file

@ -44,7 +44,6 @@
uint16_t bbBuffer[134]; uint16_t bbBuffer[134];
#endif #endif
/* Bit band SRAM definitions */ /* Bit band SRAM definitions */
#define BITBAND_SRAM_REF 0x20000000 #define BITBAND_SRAM_REF 0x20000000
#define BITBAND_SRAM_BASE 0x22000000 #define BITBAND_SRAM_BASE 0x22000000
@ -71,7 +70,6 @@ uint32_t sequence[MAX_GCR_EDGES];
int sequenceIndex = 0; int sequenceIndex = 0;
#endif #endif
static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t count, uint32_t bit) static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t count, uint32_t bit)
{ {
#ifndef DEBUG_BBDECODE #ifndef DEBUG_BBDECODE

View file

@ -42,7 +42,6 @@
#define DSHOT_TELEMETRY_DEADTIME_US (30 + 5) // 30 to switch lines and 5 to switch lines back #define DSHOT_TELEMETRY_DEADTIME_US (30 + 5) // 30 to switch lines and 5 to switch lines back
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_DATA_ZERO_INIT loadDmaBufferFn *loadDmaBuffer; extern FAST_DATA_ZERO_INIT loadDmaBufferFn *loadDmaBuffer;
uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet); uint8_t loadDmaBufferDshot(uint32_t *dmaBuffer, int stride, uint16_t packet);

View file

@ -226,7 +226,6 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig)
quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_ULTRAFAST); quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_ULTRAFAST);
for (uint8_t offset = 0; offset <= 1 && !detected; offset++) { for (uint8_t offset = 0; offset <= 1 && !detected; offset++) {
uint32_t jedecID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]); uint32_t jedecID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]);

View file

@ -48,7 +48,6 @@ typedef struct flashGeometry_s {
uint32_t jedecId; uint32_t jedecId;
} flashGeometry_t; } flashGeometry_t;
typedef enum { typedef enum {
/* /*
* When set it indicates the system was booted in memory mapped mode, flash chip is already configured by * When set it indicates the system was booted in memory mapped mode, flash chip is already configured by
@ -76,7 +75,6 @@ const flashGeometry_t *flashGetGeometry(void);
void flashMemoryMappedModeDisable(void); void flashMemoryMappedModeDisable(void);
void flashMemoryMappedModeEnable(void); void flashMemoryMappedModeEnable(void);
// //
// flash partitioning api // flash partitioning api
// //

View file

@ -274,7 +274,6 @@ void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
} }
} }
static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddress) static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddress)
{ {
if (useLongAddress) { if (useLongAddress) {
@ -332,7 +331,6 @@ busStatus_e m25p16_callbackReady(uint32_t arg)
return BUS_READY; return BUS_READY;
} }
/** /**
* Erase a sector full of bytes to all 1's at the given byte offset in the flash chip. * Erase a sector full of bytes to all 1's at the given byte offset in the flash chip.
*/ */
@ -411,7 +409,6 @@ static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, vo
fdevice->currentWriteAddress = address; fdevice->currentWriteAddress = address;
} }
static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
{ {
// The segment list cannot be in automatic storage as this routine is non-blocking // The segment list cannot be in automatic storage as this routine is non-blocking
@ -566,7 +563,6 @@ static void m25p16_pageProgramQspi(flashDevice_t *fdevice, uint32_t address, con
} }
#endif /* USE_QUADSPI */ #endif /* USE_QUADSPI */
/** /**
* Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie
* on a page boundary). * on a page boundary).

View file

@ -268,7 +268,6 @@ static void w25n_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data)
#endif #endif
} }
static void w25n_deviceReset(flashDevice_t *fdevice) static void w25n_deviceReset(flashDevice_t *fdevice)
{ {
flashDeviceIO_t *io = &fdevice->io; flashDeviceIO_t *io = &fdevice->io;
@ -373,7 +372,6 @@ bool w25n_identify(flashDevice_t *fdevice, uint32_t jedecID)
static void w25n_deviceInit(flashDevice_t *flashdev); static void w25n_deviceInit(flashDevice_t *flashdev);
void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags) void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
{ {
if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) {
@ -1018,7 +1016,6 @@ busStatus_e w25n_readBBLUTCallback(uint32_t arg)
flashDevice_t *fdevice = cb_context->fdevice; flashDevice_t *fdevice = cb_context->fdevice;
uint8_t *rxData = fdevice->io.handle.dev->bus->curSegment->u.buffers.rxData; uint8_t *rxData = fdevice->io.handle.dev->bus->curSegment->u.buffers.rxData;
cb_context->bblut->pba = (rxData[0] << 16)|rxData[1]; cb_context->bblut->pba = (rxData[0] << 16)|rxData[1];
cb_context->bblut->lba = (rxData[2] << 16)|rxData[3]; cb_context->bblut->lba = (rxData[2] << 16)|rxData[3];
@ -1030,7 +1027,6 @@ busStatus_e w25n_readBBLUTCallback(uint32_t arg)
return BUS_READY; // All done return BUS_READY; // All done
} }
void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
{ {
cb_context_t cb_context; cb_context_t cb_context;

View file

@ -57,7 +57,6 @@
#define W25Q128FV_STATUS_REGISTER_BITS 8 #define W25Q128FV_STATUS_REGISTER_BITS 8
#define W25Q128FV_ADDRESS_BITS 24 #define W25Q128FV_ADDRESS_BITS 24
// Instructions // Instructions
#define W25Q128FV_INSTRUCTION_RDID 0x9F #define W25Q128FV_INSTRUCTION_RDID 0x9F
@ -90,7 +89,6 @@
#define W25Q128FV_SR2_BIT_QUAD_ENABLE (1 << 1) #define W25Q128FV_SR2_BIT_QUAD_ENABLE (1 << 1)
//#define W25Q128FV_INSTRUCTION_WRITE_DISABLE 0x04 //#define W25Q128FV_INSTRUCTION_WRITE_DISABLE 0x04
//#define W25Q128FV_INSTRUCTION_PAGE_PROGRAM 0x02 //#define W25Q128FV_INSTRUCTION_PAGE_PROGRAM 0x02
@ -103,7 +101,6 @@
#define W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS 3 // tPPmax = 3ms, tPPtyp = 0.7ms #define W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS 3 // tPPmax = 3ms, tPPtyp = 0.7ms
#define W25Q128FV_TIMEOUT_WRITE_ENABLE_MS 1 #define W25Q128FV_TIMEOUT_WRITE_ENABLE_MS 1
typedef enum { typedef enum {
INITIAL_MODE_SPI = 0, INITIAL_MODE_SPI = 0,
INITIAL_MODE_QUADSPI, INITIAL_MODE_QUADSPI,
@ -168,7 +165,6 @@ MMFLASH_CODE static uint8_t w25q128fv_readRegister(flashDeviceIO_t *io, uint8_t
octoSpiReceive1LINE(octoSpi, command, 0, in, W25Q128FV_STATUS_REGISTER_BITS / 8); octoSpiReceive1LINE(octoSpi, command, 0, in, W25Q128FV_STATUS_REGISTER_BITS / 8);
#endif #endif
return in[0]; return in[0];
} }
@ -204,7 +200,6 @@ static void w25q128fv_deviceReset(flashDevice_t *fdevice)
w25q128fv_writeRegister(io, W25Q128FV_INSTRUCTION_WRITE_STATUS2_REG, 0x00); w25q128fv_writeRegister(io, W25Q128FV_INSTRUCTION_WRITE_STATUS2_REG, 0x00);
#endif #endif
#if defined(USE_FLASH_WRITES_USING_4LINES) || defined(USE_FLASH_READS_USING_4LINES) #if defined(USE_FLASH_WRITES_USING_4LINES) || defined(USE_FLASH_READS_USING_4LINES)
uint8_t registerValue = w25q128fv_readRegister(io, W25Q128FV_INSTRUCTION_READ_STATUS2_REG); uint8_t registerValue = w25q128fv_readRegister(io, W25Q128FV_INSTRUCTION_READ_STATUS2_REG);

View file

@ -30,7 +30,6 @@
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/serial_impl.h" #include "drivers/serial_impl.h"
#include "inverter.h" #include "inverter.h"
static const serialPinConfig_t *pSerialPinConfig; static const serialPinConfig_t *pSerialPinConfig;

View file

@ -29,7 +29,6 @@
#define DEFIO_TAG_E(pinid) CONCAT(DEFIO_TAG_E__, pinid) #define DEFIO_TAG_E(pinid) CONCAT(DEFIO_TAG_E__, pinid)
#define DEFIO_TAG_E__NONE 0 #define DEFIO_TAG_E__NONE 0
// return ioRec_t or NULL for given pinid // return ioRec_t or NULL for given pinid
// tags should be preferred, possibly removing it in future // tags should be preferred, possibly removing it in future
// io_impl.h must be included when this macro is used // io_impl.h must be included when this macro is used

View file

@ -107,8 +107,6 @@
#endif #endif
#define DEFIO_PORT_I_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) #define DEFIO_PORT_I_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT)
// DEFIO_GPIOID__<port> maps to port index // DEFIO_GPIOID__<port> maps to port index
#define DEFIO_GPIOID__A 0 #define DEFIO_GPIOID__A 0
#define DEFIO_GPIOID__B 1 #define DEFIO_GPIOID__B 1

View file

@ -200,7 +200,6 @@ bool ws2811UpdateStrip(ledStripFormatRGB_e ledFormat, uint8_t brightness)
return false; return false;
} }
// fill transmit buffer with correct compare values to achieve // fill transmit buffer with correct compare values to achieve
// correct pulse widths according to color values // correct pulse widths according to color values
const unsigned ledUpdateCount = needsFullRefresh ? WS2811_DATA_BUFFER_SIZE : usedLedCount; const unsigned ledUpdateCount = needsFullRefresh ? WS2811_DATA_BUFFER_SIZE : usedLedCount;

View file

@ -41,7 +41,6 @@
#include "drivers/osd_symbols.h" #include "drivers/osd_symbols.h"
#include "drivers/time.h" #include "drivers/time.h"
// 10 MHz max SPI frequency // 10 MHz max SPI frequency
#define MAX7456_MAX_SPI_CLK_HZ 10000000 #define MAX7456_MAX_SPI_CLK_HZ 10000000
#define MAX7456_INIT_MAX_SPI_CLK_HZ 5000000 #define MAX7456_INIT_MAX_SPI_CLK_HZ 5000000

View file

@ -41,7 +41,6 @@ typedef enum {
PWM_TYPE_MAX PWM_TYPE_MAX
} motorPwmProtocolTypes_e; } motorPwmProtocolTypes_e;
typedef struct motorVTable_s { typedef struct motorVTable_s {
// Common // Common
void (*postInit)(void); void (*postInit)(void);

View file

@ -20,7 +20,6 @@
#pragma once #pragma once
// can't use 0 // can't use 0
#define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1) #define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1)
#define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1) #define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1)

View file

@ -29,7 +29,6 @@
#include "pg/pin_pull_up_down.h" #include "pg/pin_pull_up_down.h"
#include "pin_pull_up_down.h" #include "pin_pull_up_down.h"
static void initPin(const pinPullUpDownConfig_t* config, resourceOwner_e owner, uint8_t index) static void initPin(const pinPullUpDownConfig_t* config, resourceOwner_e owner, uint8_t index)
{ {
IO_t io = IOGetByTag(config->ioTag); IO_t io = IOGetByTag(config->ioTag);

View file

@ -18,7 +18,6 @@
* If not, see <http://www.gnu.org/licenses/>. * If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <math.h> #include <math.h>
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
@ -140,12 +139,10 @@ FAST_CODE void pwmWriteDshotInt(uint8_t index, uint16_t value)
} }
#ifdef USE_DSHOT_TELEMETRY #ifdef USE_DSHOT_TELEMETRY
void dshotEnableChannels(uint8_t motorCount); void dshotEnableChannels(uint8_t motorCount);
static uint32_t decodeTelemetryPacket(const uint32_t buffer[], uint32_t count) static uint32_t decodeTelemetryPacket(const uint32_t buffer[], uint32_t count)
{ {
uint32_t value = 0; uint32_t value = 0;

View file

@ -41,7 +41,6 @@
#define HCSR04_DETECTION_CONE_DECIDEGREES 300 // recommended cone angle30 degrees, from HC-SR04 spec sheet #define HCSR04_DETECTION_CONE_DECIDEGREES 300 // recommended cone angle30 degrees, from HC-SR04 spec sheet
#define HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES 450 // in practice 45 degrees seems to work well #define HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES 450 // in practice 45 degrees seems to work well
/* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits. /* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits.
* When triggered it sends out a series of 40KHz ultrasonic pulses and receives * When triggered it sends out a series of 40KHz ultrasonic pulses and receives
* echo from an object. The distance between the unit and the object is calculated * echo from an object. The distance between the unit and the object is calculated

View file

@ -154,7 +154,6 @@ enum {
NRF24L01_04_SETUP_RETR_ARC_14 = 0x0e, NRF24L01_04_SETUP_RETR_ARC_14 = 0x0e,
NRF24L01_04_SETUP_RETR_ARC_15 = 0x0f, NRF24L01_04_SETUP_RETR_ARC_15 = 0x0f,
NRF24L01_06_RF_SETUP_RF_DR_2Mbps = 0x08, NRF24L01_06_RF_SETUP_RF_DR_2Mbps = 0x08,
NRF24L01_06_RF_SETUP_RF_DR_1Mbps = 0x00, NRF24L01_06_RF_SETUP_RF_DR_1Mbps = 0x00,
NRF24L01_06_RF_SETUP_RF_DR_250Kbps = 0x20, NRF24L01_06_RF_SETUP_RF_DR_250Kbps = 0x20,
@ -185,7 +184,6 @@ uint8_t NRF24L01_ReadReg(uint8_t reg);
void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length); void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length);
void NRF24L01_ReadPayload(uint8_t *data, uint8_t length); void NRF24L01_ReadPayload(uint8_t *data, uint8_t length);
// Utility functions // Utility functions
void NRF24L01_FlushTx(void); void NRF24L01_FlushTx(void);

View file

@ -209,7 +209,6 @@ static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture
ppmDev.overflowed = false; ppmDev.overflowed = false;
/* Store the current measurement */ /* Store the current measurement */
ppmDev.currentTime = currentTime; ppmDev.currentTime = currentTime;
ppmDev.currentCapture = capture; ppmDev.currentCapture = capture;

View file

@ -71,7 +71,6 @@ static sx1280PacketTypes_e sx1280PacketMode;
#define SX1280_BUSY_TIMEOUT_US 1000 #define SX1280_BUSY_TIMEOUT_US 1000
bool sx1280IsBusy(void) bool sx1280IsBusy(void)
{ {
return IORead(busy); return IORead(busy);
@ -940,7 +939,6 @@ static busStatus_e sx1280EnableIRQs(uint32_t arg)
return BUS_READY; return BUS_READY;
} }
// Send telemetry response // Send telemetry response
static void sx1280SendTelemetryBuffer(extiCallbackRec_t *cb) static void sx1280SendTelemetryBuffer(extiCallbackRec_t *cb)
{ {

View file

@ -35,7 +35,6 @@
#include "drivers/rx/rx_nrf24l01.h" #include "drivers/rx/rx_nrf24l01.h"
#include "drivers/rx/rx_spi.h" #include "drivers/rx/rx_spi.h"
static const uint8_t xn297_data_scramble[30] = { static const uint8_t xn297_data_scramble[30] = {
0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12, 0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12,
0x69, 0xee, 0x1f, 0xc7, 0x62, 0x97, 0xd5, 0x0b, 0x69, 0xee, 0x1f, 0xc7, 0x62, 0x97, 0xd5, 0x0b,
@ -60,7 +59,6 @@ static uint8_t bitReverse(uint8_t bIn)
return bOut; return bOut;
} }
#define RX_TX_ADDR_LEN 5 #define RX_TX_ADDR_LEN 5
uint16_t XN297_UnscramblePayload(uint8_t *data, int len, const uint8_t *rxAddr) uint16_t XN297_UnscramblePayload(uint8_t *data, int len, const uint8_t *rxAddr)

View file

@ -110,7 +110,6 @@ static void sdcard_reset(void)
} }
} }
// Called in ISR context // Called in ISR context
// Wait until idle indicated by a read value of 0xff // Wait until idle indicated by a read value of 0xff
busStatus_e sdcard_callbackIdle(uint32_t arg) busStatus_e sdcard_callbackIdle(uint32_t arg)
@ -132,7 +131,6 @@ busStatus_e sdcard_callbackIdle(uint32_t arg)
return BUS_BUSY; return BUS_BUSY;
} }
// Called in ISR context // Called in ISR context
// Wait until idle is no longer indicated by a read value of 0xff // Wait until idle is no longer indicated by a read value of 0xff
busStatus_e sdcard_callbackNotIdle(uint32_t arg) busStatus_e sdcard_callbackNotIdle(uint32_t arg)
@ -153,7 +151,6 @@ busStatus_e sdcard_callbackNotIdle(uint32_t arg)
return BUS_BUSY; return BUS_BUSY;
} }
/** /**
* The SD card spec requires 8 clock cycles to be sent by us on the bus after most commands so it can finish its * The SD card spec requires 8 clock cycles to be sent by us on the bus after most commands so it can finish its
* processing of that command. The easiest way for us to do this is to just wait for the bus to become idle before * processing of that command. The easiest way for us to do this is to just wait for the bus to become idle before

View file

@ -109,7 +109,6 @@ typedef enum
SD_SDMMC_UNKNOWN_FUNCTION = (33), SD_SDMMC_UNKNOWN_FUNCTION = (33),
SD_OUT_OF_BOUND = (34), SD_OUT_OF_BOUND = (34),
// Standard error defines // Standard error defines
SD_INTERNAL_ERROR = (35), SD_INTERNAL_ERROR = (35),
SD_NOT_CONFIGURED = (36), SD_NOT_CONFIGURED = (36),
@ -123,7 +122,6 @@ typedef enum
SD_OK = (0) SD_OK = (0)
} SD_Error_t; } SD_Error_t;
typedef struct typedef struct
{ {
uint8_t DAT_BUS_WIDTH; // Shows the currently defined data bus width uint8_t DAT_BUS_WIDTH; // Shows the currently defined data bus width

View file

@ -44,7 +44,6 @@ void serialWrite(serialPort_t *instance, uint8_t ch)
instance->vTable->serialWrite(instance, ch); instance->vTable->serialWrite(instance, ch);
} }
void serialWriteBufNoFlush(serialPort_t *instance, const uint8_t *data, int count) void serialWriteBufNoFlush(serialPort_t *instance, const uint8_t *data, int count)
{ {
if (instance->vTable->writeBuf) { if (instance->vTable->writeBuf) {

View file

@ -46,7 +46,6 @@
#include "pg/motor.h" #include "pg/motor.h"
typedef enum { typedef enum {
BAUDRATE_NORMAL = 19200, BAUDRATE_NORMAL = 19200,
BAUDRATE_SIMONK = 28800, // = 9600 * 3 BAUDRATE_SIMONK = 28800, // = 9600 * 3
@ -238,7 +237,6 @@ static void processTxStateBL(escSerial_t *escSerial)
escSerial->bitsLeftToTransmit = TX_TOTAL_BITS; escSerial->bitsLeftToTransmit = TX_TOTAL_BITS;
escSerial->isTransmittingData = true; escSerial->isTransmittingData = true;
//set output //set output
if (escSerial->mode==PROTOCOL_BLHELI || escSerial->mode==PROTOCOL_CASTLE) { if (escSerial->mode==PROTOCOL_BLHELI || escSerial->mode==PROTOCOL_CASTLE) {
escSerialOutputPortConfig(escSerial->rxTimerHardware); escSerialOutputPortConfig(escSerial->rxTimerHardware);
@ -468,7 +466,6 @@ reload:
} }
} }
// build internal buffer, data bits (MSB to LSB) // build internal buffer, data bits (MSB to LSB)
escSerial->internalTxBuffer = byteToSend; escSerial->internalTxBuffer = byteToSend;
escSerial->bitsLeftToTransmit = 8; escSerial->bitsLeftToTransmit = 8;
@ -661,7 +658,6 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
{ {
escSerial_t *escSerial = &(escSerialPorts[portIndex]); escSerial_t *escSerial = &(escSerialPorts[portIndex]);
if (mode != PROTOCOL_KISSALL) { if (mode != PROTOCOL_KISSALL) {
if (escSerialConfig()->ioTag == IO_TAG_NONE) { if (escSerialConfig()->ioTag == IO_TAG_NONE) {
@ -780,7 +776,6 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
return &escSerial->port; return &escSerial->port;
} }
static void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr) static void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr)
{ {
timerChClearCCFlag(timerHardwarePtr); timerChClearCCFlag(timerHardwarePtr);
@ -788,7 +783,6 @@ static void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr)
escSerialGPIOConfig(timerHardwarePtr, IOCFG_IPU); escSerialGPIOConfig(timerHardwarePtr, IOCFG_IPU);
} }
static void closeEscSerial(escSerialPortIndex_e portIndex, uint8_t mode) static void closeEscSerial(escSerialPortIndex_e portIndex, uint8_t mode)
{ {
escSerial_t *escSerial = &(escSerialPorts[portIndex]); escSerial_t *escSerial = &(escSerialPorts[portIndex]);
@ -951,7 +945,6 @@ static bool processExitCommand(uint8_t c)
return false; return false;
} }
bool escEnablePassthrough(serialPort_t *escPassthroughPort, const motorDevConfig_t *motorConfig, uint16_t escIndex, uint8_t mode) bool escEnablePassthrough(serialPort_t *escPassthroughPort, const motorDevConfig_t *motorConfig, uint16_t escIndex, uint8_t mode)
{ {
bool exitEsc = false; bool exitEsc = false;

View file

@ -3,7 +3,6 @@
#include "platform.h" #include "platform.h"
#include "io/serial.h" #include "io/serial.h"
#include "serial.h" #include "serial.h"
@ -36,4 +35,3 @@ bool serialOptions_pushPull(portOptions_e options)
return options & (SERIAL_INVERTED | SERIAL_BIDIR_PP); return options & (SERIAL_INVERTED | SERIAL_BIDIR_PP);
} }

View file

@ -36,4 +36,3 @@ typedef enum { serialPullNone = 0, serialPullDown = 1, serialPullUp = 2 } serial
serialPullMode_t serialOptions_pull(portOptions_e options); serialPullMode_t serialOptions_pull(portOptions_e options);
bool serialOptions_pushPull(portOptions_e options); bool serialOptions_pushPull(portOptions_e options);

View file

@ -100,5 +100,4 @@ void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
} }
} }
#endif #endif

View file

@ -326,7 +326,6 @@ serialPort_t *softSerialOpen(serialPortIdentifier_e identifier, serialReceiveCal
return &softSerial->port; return &softSerial->port;
} }
/* /*
* Serial Engine * Serial Engine
*/ */
@ -534,7 +533,6 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
#endif #endif
} }
/* /*
* Standard serial driver API * Standard serial driver API
*/ */

View file

@ -606,5 +606,4 @@ UART_IRQHandler(UART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler
#endif #endif
#endif // USE_UART #endif // USE_UART

View file

@ -32,7 +32,6 @@
#include "drivers/resource.h" #include "drivers/resource.h"
#include "drivers/sound_beeper.h" #include "drivers/sound_beeper.h"
#include "system.h" #include "system.h"
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F4) || defined(APM32F4) #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F4) || defined(APM32F4)

View file

@ -35,7 +35,6 @@
#define TRANSPONDER_TRANSMIT_JITTER_ARCITIMER 10000 #define TRANSPONDER_TRANSMIT_JITTER_ARCITIMER 10000
/*** ******** ***/ /*** ******** ***/
/*** ILAP ***/ /*** ILAP ***/
#define TRANSPONDER_BITS_PER_BYTE_ILAP 10 // start + 8 data + stop #define TRANSPONDER_BITS_PER_BYTE_ILAP 10 // start + 8 data + stop
#define TRANSPONDER_DATA_LENGTH_ILAP 6 #define TRANSPONDER_DATA_LENGTH_ILAP 6
@ -49,7 +48,6 @@
#define TRANSPONDER_TRANSMIT_JITTER_ILAP 10000 #define TRANSPONDER_TRANSMIT_JITTER_ILAP 10000
/*** ******** ***/ /*** ******** ***/
/*** ERLT ***/ /*** ERLT ***/
#define TRANSPONDER_DATA_LENGTH_ERLT 1 #define TRANSPONDER_DATA_LENGTH_ERLT 1
@ -63,7 +61,6 @@
#define TRANSPONDER_TRANSMIT_JITTER_ERLT 5000 #define TRANSPONDER_TRANSMIT_JITTER_ERLT 5000
/*** ******** ***/ /*** ******** ***/
/* /*
* Implementation note: * Implementation note:
* Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast * Using around over 700 bytes for a transponder DMA buffer is a little excessive, likely an alternative implementation that uses a fast

View file

@ -66,8 +66,6 @@ void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8
dmaBufferOffset = 0; dmaBufferOffset = 0;
} }
const struct transponderVTable arcitimerTansponderVTable = { const struct transponderVTable arcitimerTansponderVTable = {
updateTransponderDMABufferArcitimer, updateTransponderDMABufferArcitimer,
}; };

View file

@ -34,7 +34,5 @@
// ID8 0xFF, 0x3, 0xF0, 0x1, 0xF8, 0xE0, 0xC1, 0xFF, 0x1 // 00FC0FFE071F3E00FE // ID8 0xFF, 0x3, 0xF0, 0x1, 0xF8, 0xE0, 0xC1, 0xFF, 0x1 // 00FC0FFE071F3E00FE
// ID9 0x1F, 0x7C, 0x40, 0xF, 0xF0, 0x61, 0xC7, 0x3F, 0x0 // E083BFF00F9E38C0FF // ID9 0x1F, 0x7C, 0x40, 0xF, 0xF0, 0x61, 0xC7, 0x3F, 0x0 // E083BFF00F9E38C0FF
void transponderIrInitArcitimer(transponder_t *transponder); void transponderIrInitArcitimer(transponder_t *transponder);
void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData); void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData);

View file

@ -33,7 +33,6 @@
#include "drivers/vtx_common.h" #include "drivers/vtx_common.h"
#include "drivers/vtx_table.h" #include "drivers/vtx_table.h"
static vtxDevice_t *vtxDevice = NULL; static vtxDevice_t *vtxDevice = NULL;
static uint8_t selectedBand = 0; static uint8_t selectedBand = 0;
static uint8_t selectedChannel = 0; static uint8_t selectedChannel = 0;

View file

@ -95,7 +95,6 @@ typedef struct vtxDevice_s {
const struct vtxVTable_s *const vTable; const struct vtxVTable_s *const vTable;
} vtxDevice_t; } vtxDevice_t;
// {set,get}BandAndChannel: band and channel are 1 origin // {set,get}BandAndChannel: band and channel are 1 origin
// {set,get}PowerByIndex: 0 = Power OFF, 1 = device dependent // {set,get}PowerByIndex: 0 = Power OFF, 1 = device dependent
// {set,get}PitMode: 0 = OFF, 1 = ON // {set,get}PitMode: 0 = OFF, 1 = ON

View file

@ -44,4 +44,3 @@ void rtc6705SetRFPower(uint8_t rf_power);
void rtc6705Disable(void); void rtc6705Disable(void);
void rtc6705Enable(void); void rtc6705Enable(void);

View file

@ -31,7 +31,6 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/vtx_rtc6705.h" #include "drivers/vtx_rtc6705.h"
#define DP_5G_MASK 0x7000 #define DP_5G_MASK 0x7000
#define PA5G_BS_MASK 0x0E00 #define PA5G_BS_MASK 0x0E00
#define PA5G_PW_MASK 0x0180 #define PA5G_PW_MASK 0x0180
@ -54,7 +53,6 @@ static IO_t rtc6705DataPin = IO_NONE;
static IO_t rtc6705CsnPin = IO_NONE; static IO_t rtc6705CsnPin = IO_NONE;
static IO_t rtc6705ClkPin = IO_NONE; static IO_t rtc6705ClkPin = IO_NONE;
bool rtc6705SoftSpiIOInit(const vtxIOConfig_t *vtxIOConfig, const IO_t csnPin) bool rtc6705SoftSpiIOInit(const vtxIOConfig_t *vtxIOConfig, const IO_t csnPin)
{ {
rtc6705CsnPin = csnPin; rtc6705CsnPin = csnPin;

View file

@ -28,4 +28,3 @@ bool rtc6705SoftSpiIOInit(const vtxIOConfig_t *vtxIOConfig, const IO_t csnPin);
void rtc6705SoftSpiSetFrequency(uint16_t freq); void rtc6705SoftSpiSetFrequency(uint16_t freq);
void rtc6705SoftSpiSetRFPower(uint8_t rf_power); void rtc6705SoftSpiSetRFPower(uint8_t rf_power);

Some files were not shown because too many files have changed in this diff Show more