1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

Refactor missing prototypes 2 (#14170)

This commit is contained in:
Petr Ledvina 2025-01-28 20:20:12 +01:00 committed by GitHub
parent 25f65cbc01
commit b277364b2c
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
192 changed files with 487 additions and 410 deletions

View file

@ -20,13 +20,13 @@
#include "platform.h"
#include "debug_pin.h"
#ifdef USE_DEBUG_PIN
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "debug_pin.h"
typedef struct dbgPinState_s {
GPIO_TypeDef *gpio;
uint32_t setBSRR;

View file

@ -339,31 +339,37 @@ static void cliWriterFlush(void)
cliWriterFlushInternal(cliWriter);
}
void cliPrint(const char *str)
#ifdef USE_CLI_DEBUG_PRINT
#define CLI_DEBUG_EXPORT /* empty */
#else
#define CLI_DEBUG_EXPORT static
#endif
CLI_DEBUG_EXPORT void cliPrint(const char *str)
{
cliPrintInternal(cliWriter, str);
}
void cliPrintLinefeed(void)
CLI_DEBUG_EXPORT void cliPrintLinefeed(void)
{
cliPrint("\r\n");
}
void cliPrintLine(const char *str)
CLI_DEBUG_EXPORT void cliPrintLine(const char *str)
{
cliPrint(str);
cliPrintLinefeed();
}
#ifdef MINIMAL_CLI
#define cliPrintHashLine(str)
#else
static void cliPrintHashLine(const char *str)
{
#ifndef MINIMAL_CLI
cliPrint("\r\n# ");
cliPrintLine(str);
}
#else
UNUSED(str);
#endif
}
static void cliPutp(void *p, char ch)
{
@ -415,7 +421,7 @@ static bool cliDefaultPrintLinef(dumpFlags_t dumpMask, bool equalsDefault, const
}
}
void cliPrintf(const char *format, ...)
CLI_DEBUG_EXPORT void cliPrintf(const char *format, ...)
{
va_list va;
va_start(va, format);
@ -423,7 +429,7 @@ void cliPrintf(const char *format, ...)
va_end(va);
}
void cliPrintLinef(const char *format, ...)
CLI_DEBUG_EXPORT void cliPrintLinef(const char *format, ...)
{
va_list va;
va_start(va, format);
@ -3228,7 +3234,7 @@ static void cliManufacturerId(const char *cmdName, char *cmdline)
}
#if defined(USE_SIGNATURE)
static void writeSignature(char *signatureStr, uint8_t *signature)
static void writeSignature(char *signatureStr, const uint8_t *signature)
{
for (unsigned i = 0; i < SIGNATURE_LENGTH; i++) {
tfp_sprintf(&signatureStr[2 * i], "%02x", signature[i]);
@ -4269,7 +4275,7 @@ static bool prepareSave(void)
return true;
}
bool tryPrepareSave(const char *cmdName)
static bool tryPrepareSave(const char *cmdName)
{
bool success = prepareSave();
#if defined(USE_CLI_BATCH)
@ -4443,7 +4449,7 @@ static uint8_t getWordLength(const char *bufBegin, const char *bufEnd)
return bufEnd - bufBegin;
}
uint16_t cliGetSettingIndex(const char *name, size_t length)
STATIC_UNIT_TESTED uint16_t cliGetSettingIndex(const char *name, size_t length)
{
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
const char *settingName = valueTable[i].name;

View file

@ -1375,7 +1375,7 @@ void cmsSetExternKey(cms_key_e extKey)
externKey = extKey;
}
uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, cms_key_e key, int repeatCount)
static uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, cms_key_e key, int repeatCount)
{
uint16_t ret = 0;

View file

@ -41,6 +41,8 @@
#include "io/vtx_msp.h"
#include "io/vtx.h"
#include "cms_menu_vtx_msp.h"
char mspCmsStatusString[31] = "- -- ---- ----";
// m bc ffff tppp
// 01234567890123

View file

@ -27,4 +27,4 @@ extern CMS_Menu cmsx_menuVtxSmartAudio;
void saCmsUpdate(void);
void saUpdateStatusString(void);
void saCmsResetOpmodel();
void saCmsResetOpmodel(void);

View file

@ -41,6 +41,8 @@
#include "io/vtx_tramp.h"
#include "io/vtx.h"
#include "cms_menu_vtx_tramp.h"
char trampCmsStatusString[31] = "- -- ---- ----";
// m bc ffff tppp
// 01234567890123

View file

@ -32,6 +32,8 @@ Stripped down for BF use
#include "platform.h"
#include "common/maths.h"
/* Workaround a lack of optimization in gcc */
float exp_cst1 = 2139095040.f;
float exp_cst2 = 0.f;

View file

@ -25,6 +25,8 @@
#include "platform.h"
#include "gps_conversion.h"
#ifdef USE_GPS
#define DIGIT_TO_VAL(_x) (_x - '0')

View file

@ -26,9 +26,11 @@
#include "common/utils.h"
#include "strtol.h"
#define _STRTO_ENDPTR 1
unsigned long _strto_l(const char * str, char ** endptr, int base, int sflag)
static unsigned long _strto_l(const char * str, char ** endptr, int base, int sflag)
{
unsigned long number, cutoff;
#if _STRTO_ENDPTR

View file

@ -26,7 +26,9 @@
#include "platform.h"
#include "build/build_config.h"
#include "maths.h"
#include "common/maths.h"
#include "typeconversion.h"
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
@ -86,7 +88,7 @@ void i2a(int num, char *bf)
ui2a(num, 10, 0, bf);
}
int a2d(char ch)
static int a2d(char ch)
{
if (ch >= '0' && ch <= '9')
return ch - '0';

View file

@ -58,6 +58,9 @@
#define UNUSED(x) (void)(x) // Variables and parameters that are not used
#endif
#define MAYBE_UNUSED __attribute__ ((unused))
#define LOCAL_UNUSED_FUNCTION __attribute__ ((unused, deprecated ("function is marked as LOCAL_UNUSED_FUNCTION")))
#define DISCARD(x) (void)(x) // To explicitly ignore result of x (usually an I/O register access).
#ifndef __cplusplus

View file

@ -217,7 +217,7 @@ static void validateAndFixConfig(void)
#endif
if (!isSerialConfigValid(serialConfigMutable())) {
pgResetFn_serialConfig(serialConfigMutable());
PG_RESET(serialConfig);
}
#if defined(USE_GPS)

View file

@ -87,7 +87,7 @@ typedef struct {
} PG_PACKED packingTest_t;
#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH)
MMFLASH_CODE bool loadEEPROMFromExternalFlash(void)
static MMFLASH_CODE bool loadEEPROMFromExternalFlash(void)
{
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG);
const flashGeometry_t *flashGeometry = flashGetGeometry();

View file

@ -267,7 +267,7 @@ extiCallbackRec_t bmi160IntCallbackRec;
// Called in ISR context
// Gyro read has just completed
busStatus_e bmi160Intcallback(uint32_t arg)
static busStatus_e bmi160Intcallback(uint32_t arg)
{
gyroDev_t *gyro = (gyroDev_t *)arg;
int32_t gyroDmaDuration = cmpTimeCycles(getCycleCounter(), gyro->gyroLastEXTI);
@ -281,7 +281,7 @@ busStatus_e bmi160Intcallback(uint32_t arg)
return BUS_READY;
}
void bmi160ExtiHandler(extiCallbackRec_t *cb)
static void bmi160ExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
extDevice_t *dev = &gyro->dev;
@ -440,7 +440,7 @@ static bool bmi160GyroRead(gyroDev_t *gyro)
return true;
}
void bmi160SpiGyroInit(gyroDev_t *gyro)
static void bmi160SpiGyroInit(gyroDev_t *gyro)
{
extDevice_t *dev = &gyro->dev;
@ -450,7 +450,7 @@ void bmi160SpiGyroInit(gyroDev_t *gyro)
spiSetClkDivisor(dev, spiCalculateDivider(BMI160_MAX_SPI_CLK_HZ));
}
void bmi160SpiAccInit(accDev_t *acc)
static void bmi160SpiAccInit(accDev_t *acc)
{
acc->acc_1G = 512 * 8;
}

View file

@ -278,7 +278,7 @@ extiCallbackRec_t bmi270IntCallbackRec;
*/
// Called in ISR context
// Gyro read has just completed
busStatus_e bmi270Intcallback(uint32_t arg)
static busStatus_e bmi270Intcallback(uint32_t arg)
{
gyroDev_t *gyro = (gyroDev_t *)arg;
int32_t gyroDmaDuration = cmpTimeCycles(getCycleCounter(), gyro->gyroLastEXTI);
@ -292,7 +292,7 @@ busStatus_e bmi270Intcallback(uint32_t arg)
return BUS_READY;
}
void bmi270ExtiHandler(extiCallbackRec_t *cb)
static void bmi270ExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
extDevice_t *dev = &gyro->dev;

View file

@ -856,7 +856,7 @@ uint8_t lsm6dsv16xSpiDetect(const extDevice_t *dev)
return LSM6DSV16X_SPI;
}
void lsm6dsv16xAccInit(accDev_t *acc)
static void lsm6dsv16xAccInit(accDev_t *acc)
{
// ±16G mode
acc->acc_1G = 512 * 4;
@ -924,7 +924,7 @@ bool lsm6dsv16xSpiAccDetect(accDev_t *acc)
return true;
}
void lsm6dsv16xGyroInit(gyroDev_t *gyro)
static void lsm6dsv16xGyroInit(gyroDev_t *gyro)
{
const extDevice_t *dev = &gyro->dev;
// Set default LPF1 filter bandwidth to be as close as possible to MPU6000's 250Hz cutoff
@ -1009,7 +1009,7 @@ void lsm6dsv16xGyroInit(gyroDev_t *gyro)
mpuGyroInit(gyro);
}
bool lsm6dsv16xGyroReadSPI(gyroDev_t *gyro)
static bool lsm6dsv16xGyroReadSPI(gyroDev_t *gyro)
{
int16_t *gyroData = (int16_t *)gyro->dev.rxBuf;
switch (gyro->gyroModeSPI) {

View file

@ -100,7 +100,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro);
#define MPU6000_REV_D9 0x59
#define MPU6000_REV_D10 0x5A
void mpu6000SpiGyroInit(gyroDev_t *gyro)
static void mpu6000SpiGyroInit(gyroDev_t *gyro)
{
extDevice_t *dev = &gyro->dev;
@ -121,7 +121,7 @@ void mpu6000SpiGyroInit(gyroDev_t *gyro)
}
}
void mpu6000SpiAccInit(accDev_t *acc)
static void mpu6000SpiAccInit(accDev_t *acc)
{
acc->acc_1G = 512 * 4;
}

View file

@ -69,7 +69,7 @@ static bool mpu9250SpiSlowReadRegisterBuffer(const extDevice_t *dev, uint8_t reg
return true;
}
void mpu9250SpiGyroInit(gyroDev_t *gyro)
static void mpu9250SpiGyroInit(gyroDev_t *gyro)
{
extDevice_t *dev = &gyro->dev;
@ -86,7 +86,7 @@ void mpu9250SpiGyroInit(gyroDev_t *gyro)
}
}
void mpu9250SpiAccInit(accDev_t *acc)
static void mpu9250SpiAccInit(accDev_t *acc)
{
acc->acc_1G = 512 * 4;
}

View file

@ -73,8 +73,10 @@ typedef struct adcTagMap_s {
#define ADC_DEVICES_345 ((1 << ADCDEV_3)|(1 << ADCDEV_4)|(1 << ADCDEV_5))
typedef struct adcDevice_s {
#if !defined(SIMULATOR_BUILD)
ADC_TypeDef* ADCx;
rccPeriphTag_t rccADC;
#endif
#if !defined(USE_DMA_SPEC)
dmaResource_t* dmaResource;
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
@ -104,7 +106,9 @@ extern adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
uint8_t adcChannelByTag(ioTag_t ioTag);
#if !defined(SIMULATOR_BUILD)
ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance);
#endif
bool adcVerifyPin(ioTag_t tag, ADCDevice device);
// Marshall values in DMA instance/channel based order to adcChannel based order.

View file

@ -117,7 +117,7 @@ static bool bmp280GetUP(baroDev_t *baro);
STATIC_UNIT_TESTED void bmp280Calculate(int32_t *pressure, int32_t *temperature);
void bmp280BusInit(const extDevice_t *dev)
static void bmp280BusInit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_BMP280
if (dev->bus->busType == BUS_TYPE_SPI) {
@ -131,7 +131,7 @@ void bmp280BusInit(const extDevice_t *dev)
#endif
}
void bmp280BusDeinit(const extDevice_t *dev)
static void bmp280BusDeinit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_BMP280
if (dev->bus->busType == BUS_TYPE_SPI) {

View file

@ -198,7 +198,7 @@ static bool bmp388ReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_
}
}
void bmp388_extiHandler(extiCallbackRec_t* cb)
static void bmp388_extiHandler(extiCallbackRec_t* cb)
{
#ifdef DEBUG
static uint32_t bmp388ExtiCallbackCounter = 0;
@ -212,7 +212,7 @@ void bmp388_extiHandler(extiCallbackRec_t* cb)
bmp388ReadRegisterBuffer(&baro->dev, BMP388_INT_STATUS_REG, &intStatus, 1);
}
void bmp388BusInit(const extDevice_t *dev)
static void bmp388BusInit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_BMP388
if (dev->bus->busType == BUS_TYPE_SPI) {
@ -226,7 +226,7 @@ void bmp388BusInit(const extDevice_t *dev)
#endif
}
void bmp388BusDeinit(const extDevice_t *dev)
static void bmp388BusDeinit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_BMP388
if (dev->bus->busType == BUS_TYPE_SPI) {
@ -237,7 +237,7 @@ void bmp388BusDeinit(const extDevice_t *dev)
#endif
}
bool bmp388BeginForcedMeasurement(const extDevice_t *dev)
static bool bmp388BeginForcedMeasurement(const extDevice_t *dev)
{
// enable pressure measurement, temperature measurement, set power mode and start sampling
uint8_t mode = BMP388_MODE_FORCED << 4 | 1 << 1 | 1 << 0;

View file

@ -191,17 +191,17 @@
static uint32_t rawP = 0;
static uint16_t rawT = 0;
bool lpsWriteCommand(const extDevice_t *dev, uint8_t cmd, uint8_t byte)
static bool lpsWriteCommand(const extDevice_t *dev, uint8_t cmd, uint8_t byte)
{
return spiWriteRegRB(dev, cmd, byte);
}
bool lpsReadCommand(const extDevice_t *dev, uint8_t cmd, uint8_t *data, uint8_t len)
static bool lpsReadCommand(const extDevice_t *dev, uint8_t cmd, uint8_t *data, uint8_t len)
{
return spiReadRegMskBufRB(dev, cmd | 0x80 | 0x40, data, len);
}
bool lpsWriteVerify(const extDevice_t *dev, uint8_t cmd, uint8_t byte)
static bool lpsWriteVerify(const extDevice_t *dev, uint8_t cmd, uint8_t byte)
{
uint8_t temp = 0xff;
spiWriteReg(dev, cmd, byte);

View file

@ -227,7 +227,7 @@ static bool lps22dfGetUP(baroDev_t *baro);
STATIC_UNIT_TESTED void lps22dfCalculate(int32_t *pressure, int32_t *temperature);
void lps22dfBusInit(const extDevice_t *dev)
static void lps22dfBusInit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_LPS22DF
if (dev->bus->busType == BUS_TYPE_SPI) {
@ -241,7 +241,7 @@ void lps22dfBusInit(const extDevice_t *dev)
#endif
}
void lps22dfBusDeinit(const extDevice_t *dev)
static void lps22dfBusDeinit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_LPS22DF
if (dev->bus->busType == BUS_TYPE_SPI) {

View file

@ -62,7 +62,7 @@ static uint8_t ms5611_osr = CMD_ADC_4096;
#define MS5611_DATA_FRAME_SIZE 3
static DMA_DATA_ZERO_INIT uint8_t sensor_data[MS5611_DATA_FRAME_SIZE];
void ms5611BusInit(const extDevice_t *dev)
static void ms5611BusInit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_MS5611
if (dev->bus->busType == BUS_TYPE_SPI) {
@ -76,7 +76,7 @@ void ms5611BusInit(const extDevice_t *dev)
#endif
}
void ms5611BusDeinit(const extDevice_t *dev)
static void ms5611BusDeinit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_MS5611
if (dev->bus->busType == BUS_TYPE_SPI) {

View file

@ -105,7 +105,7 @@ static bool qmp6988GetUP(baroDev_t *baro);
STATIC_UNIT_TESTED void qmp6988Calculate(int32_t *pressure, int32_t *temperature);
void qmp6988BusInit(const extDevice_t *dev)
static void qmp6988BusInit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_QMP6988
if (dev->bus->busType == BUS_TYPE_SPI) {
@ -119,7 +119,7 @@ void qmp6988BusInit(const extDevice_t *dev)
#endif
}
void qmp6988BusDeinit(const extDevice_t *dev)
static void qmp6988BusDeinit(const extDevice_t *dev)
{
#ifdef USE_BARO_SPI_QMP6988
if (dev->bus->busType == BUS_TYPE_SPI) {

View file

@ -28,6 +28,7 @@
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_busdev.h"
static uint8_t i2cRegisteredDeviceCount = 0;

View file

@ -27,5 +27,5 @@ uint8_t i2cBusReadRegister(const extDevice_t *dev, uint8_t reg);
bool i2cBusReadRegisterBufferStart(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length);
bool i2cBusBusy(const extDevice_t *dev, bool *error);
// Associate a device with an I2C bus
bool i2cBusSetInstance(const extDevice_t *dev, uint32_t device);
bool i2cBusSetInstance(extDevice_t *dev, uint32_t device);
void i2cBusDeviceRegister(const extDevice_t *dev);

View file

@ -22,6 +22,8 @@
#include "platform.h"
#include "bus_i2c_timing.h"
/*
* Compute SCLDEL, SDADEL, SCLH and SCLL for TIMINGR register according to reference manuals.
*/

View file

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

View file

@ -25,6 +25,7 @@
#ifdef USE_SPI
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/resource.h"
#include "drivers/system.h"

View file

@ -372,7 +372,7 @@ static bool ak8963Init(magDev_t *mag)
return true;
}
void ak8963BusInit(const extDevice_t *dev)
static void ak8963BusInit(const extDevice_t *dev)
{
switch (dev->bus->busType) {
#ifdef USE_MAG_AK8963
@ -409,7 +409,7 @@ void ak8963BusInit(const extDevice_t *dev)
}
}
void ak8963BusDeInit(const extDevice_t *dev)
static void ak8963BusDeInit(const extDevice_t *dev)
{
switch (dev->bus->busType) {
#ifdef USE_MAG_AK8963

View file

@ -35,6 +35,8 @@
#include "drivers/time.h"
#include "common/axis.h"
#include "compass_lis2mdl.h"
#define LIS2MDL_MAG_I2C_ADDRESS 0x1E
// LIS2MDL Registers

View file

@ -31,6 +31,8 @@
#include "drivers/time.h"
#include "common/axis.h"
#include "compass_lis3mdl.h"
#define LIS3MDL_MAG_I2C_ADDRESS 0x1E
#define LIS3MDL_DEVICE_ID 0x3D

View file

@ -29,6 +29,8 @@
#include "platform.h"
#include "dshot.h"
#ifdef USE_DSHOT
#include "build/debug.h"
@ -50,8 +52,6 @@
#include "rx/rx.h"
#include "dshot.h"
#define ERPM_PER_LSB 100.0f
FAST_DATA_ZERO_INIT uint8_t dshotMotorCount = 0;

View file

@ -39,6 +39,6 @@ typedef enum {
} dshotBitbangStatus_e;
bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig);
dshotBitbangStatus_e dshotBitbangGetStatus();
dshotBitbangStatus_e dshotBitbangGetStatus(void);
const timerHardware_t *dshotBitbangTimerGetAllocatedByNumberAndChannel(int8_t timerNumber, uint16_t timerChannel);
const resourceOwner_t *dshotBitbangTimerGetOwner(const timerHardware_t *timer);

View file

@ -360,7 +360,7 @@ void flashPreinit(const flashConfig_t *flashConfig)
ioPreinitByTag(flashConfig->csTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
}
bool flashDeviceInit(const flashConfig_t *flashConfig)
static bool flashDeviceInit(const flashConfig_t *flashConfig)
{
bool haveFlash = false;

View file

@ -248,7 +248,7 @@ bool m25p16_identify(flashDevice_t *fdevice, uint32_t jedecID)
return true;
}
void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
static void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
{
if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) {
return;
@ -289,7 +289,7 @@ static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLon
// Called in ISR context
// A write enable has just been issued
busStatus_e m25p16_callbackWriteEnable(uint32_t arg)
static busStatus_e m25p16_callbackWriteEnable(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
@ -301,7 +301,7 @@ busStatus_e m25p16_callbackWriteEnable(uint32_t arg)
// Called in ISR context
// Write operation has just completed
busStatus_e m25p16_callbackWriteComplete(uint32_t arg)
static busStatus_e m25p16_callbackWriteComplete(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
@ -317,7 +317,7 @@ busStatus_e m25p16_callbackWriteComplete(uint32_t arg)
// Called in ISR context
// Check if the status was busy and if so repeat the poll
busStatus_e m25p16_callbackReady(uint32_t arg)
static busStatus_e m25p16_callbackReady(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
extDevice_t *dev = fdevice->io.handle.dev;

View file

@ -171,7 +171,7 @@ bool w25m_identify(flashDevice_t *fdevice, uint32_t jedecID)
return true;
}
void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
static void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
{
for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) {
w25m_dieSelect(fdevice->io.handle.dev, dieNumber);
@ -179,7 +179,7 @@ void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
}
}
void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
static void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
{
int dieNumber = address / dieSize;
@ -188,7 +188,7 @@ void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
dieDevice[dieNumber].vTable->eraseSector(&dieDevice[dieNumber], address % dieSize);
}
void w25m_eraseCompletely(flashDevice_t *fdevice)
static void w25m_eraseCompletely(flashDevice_t *fdevice)
{
for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) {
w25m_dieSelect(fdevice->io.handle.dev, dieNumber);
@ -199,7 +199,7 @@ void w25m_eraseCompletely(flashDevice_t *fdevice)
static uint32_t currentWriteAddress;
static int currentWriteDie;
void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
static void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
currentWriteDie = address / dieSize;
w25m_dieSelect(fdevice->io.handle.dev, currentWriteDie);
@ -207,21 +207,21 @@ void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*call
dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], address, callback);
}
uint32_t w25m_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
static uint32_t w25m_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
{
UNUSED(fdevice);
return dieDevice[currentWriteDie].vTable->pageProgramContinue(&dieDevice[currentWriteDie], buffers, bufferSizes, bufferCount);
}
void w25m_pageProgramFinish(flashDevice_t *fdevice)
static void w25m_pageProgramFinish(flashDevice_t *fdevice)
{
UNUSED(fdevice);
dieDevice[currentWriteDie].vTable->pageProgramFinish(&dieDevice[currentWriteDie]);
}
void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
static void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
w25m_pageProgramBegin(fdevice, address, callback);
@ -230,7 +230,7 @@ void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *d
w25m_pageProgramFinish(fdevice);
}
int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
static int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{
int rlen; // remaining length
int tlen; // transfer length for a round
@ -258,7 +258,7 @@ int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, ui
return length;
}
const flashGeometry_t* w25m_getGeometry(flashDevice_t *fdevice)
static const flashGeometry_t* w25m_getGeometry(flashDevice_t *fdevice)
{
return &fdevice->geometry;
}

View file

@ -288,7 +288,7 @@ static void w25n_deviceReset(flashDevice_t *fdevice)
w25n_writeRegister(io, W25N_CONF_REG, W25N_CONFIG_ECC_ENABLE|W25N_CONFIG_BUFFER_READ_MODE);
}
bool w25n_isReady(flashDevice_t *fdevice)
static bool w25n_isReady(flashDevice_t *fdevice)
{
// If we're waiting on DMA completion, then SPI is busy
if (fdevice->io.mode == FLASHIO_SPI) {
@ -372,7 +372,7 @@ bool w25n_identify(flashDevice_t *fdevice, uint32_t jedecID)
static void w25n_deviceInit(flashDevice_t *flashdev);
void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
static void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
{
if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) {
return;
@ -404,7 +404,7 @@ void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
/**
* Erase a sector full of bytes to all 1's at the given byte offset in the flash chip.
*/
void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address)
static void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address)
{
w25n_waitForReady(fdevice);
@ -420,7 +420,7 @@ void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address)
// W25N01G does not support full chip erase.
// Call eraseSector repeatedly.
void w25n_eraseCompletely(flashDevice_t *fdevice)
static void w25n_eraseCompletely(flashDevice_t *fdevice)
{
for (uint32_t block = 0; block < fdevice->geometry.sectors; block++) {
w25n_eraseSector(fdevice, W25N_BLOCK_TO_LINEAR(block));
@ -537,7 +537,7 @@ bool bufferDirty = false;
// Called in ISR context
// Check if the status was busy and if so repeat the poll
busStatus_e w25n_callbackReady(uint32_t arg)
static busStatus_e w25n_callbackReady(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
extDevice_t *dev = fdevice->io.handle.dev;
@ -557,7 +557,7 @@ busStatus_e w25n_callbackReady(uint32_t arg)
#ifdef USE_QUADSPI
bool isProgramming = false;
void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
static void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
fdevice->callback = callback;
@ -579,7 +579,7 @@ void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*call
}
}
uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
static uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
{
if (bufferCount < 1) {
fdevice->callback(0);
@ -612,7 +612,7 @@ uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffer
static uint32_t currentPage = UINT32_MAX;
void w25n_pageProgramFinish(flashDevice_t *fdevice)
static void w25n_pageProgramFinish(flashDevice_t *fdevice)
{
if (bufferDirty && W25N_LINEAR_TO_COLUMN(programLoadAddress) == 0) {
@ -627,7 +627,7 @@ void w25n_pageProgramFinish(flashDevice_t *fdevice)
}
}
#else
void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
static void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
fdevice->callback = callback;
fdevice->currentWriteAddress = address;
@ -638,7 +638,7 @@ static uint32_t currentPage = UINT32_MAX;
// Called in ISR context
// A write enable has just been issued
busStatus_e w25n_callbackWriteEnable(uint32_t arg)
static busStatus_e w25n_callbackWriteEnable(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
@ -650,7 +650,7 @@ busStatus_e w25n_callbackWriteEnable(uint32_t arg)
// Called in ISR context
// Write operation has just completed
busStatus_e w25n_callbackWriteComplete(uint32_t arg)
static busStatus_e w25n_callbackWriteComplete(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
@ -663,7 +663,7 @@ busStatus_e w25n_callbackWriteComplete(uint32_t arg)
return BUS_READY;
}
uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
static uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
{
if (bufferCount < 1) {
fdevice->callback(0);
@ -771,7 +771,7 @@ uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffer
return fdevice->callbackArg;
}
void w25n_pageProgramFinish(flashDevice_t *fdevice)
static void w25n_pageProgramFinish(flashDevice_t *fdevice)
{
UNUSED(fdevice);
}
@ -793,14 +793,14 @@ void w25n_pageProgramFinish(flashDevice_t *fdevice)
* break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call.
*/
void w25n_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
static void w25n_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
w25n_pageProgramBegin(fdevice, address, callback);
w25n_pageProgramContinue(fdevice, &data, &length, 1);
w25n_pageProgramFinish(fdevice);
}
void w25n_flush(flashDevice_t *fdevice)
static void w25n_flush(flashDevice_t *fdevice)
{
if (bufferDirty) {
currentPage = W25N_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
@ -811,7 +811,7 @@ void w25n_flush(flashDevice_t *fdevice)
}
}
void w25n_addError(uint32_t address, uint8_t code)
static void w25n_addError(uint32_t address, uint8_t code)
{
UNUSED(address);
UNUSED(code);
@ -837,7 +837,7 @@ void w25n_addError(uint32_t address, uint8_t code)
// (3) Issue READ_DATA on column address.
// (4) Return transferLength.
int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
static int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{
uint32_t targetPage = W25N_LINEAR_TO_PAGE(address);
@ -928,7 +928,7 @@ int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, ui
return transferLength;
}
int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
LOCAL_UNUSED_FUNCTION static int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
{
if (!w25n_waitForReady(fdevice)) {
@ -981,7 +981,7 @@ int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *b
*
* Can be called before calling w25n_init() (the result would have totalSize = 0).
*/
const flashGeometry_t* w25n_getGeometry(flashDevice_t *fdevice)
static const flashGeometry_t* w25n_getGeometry(flashDevice_t *fdevice)
{
return &fdevice->geometry;
}
@ -1010,7 +1010,7 @@ typedef volatile struct cb_context_s {
// Called in ISR context
// Read of BBLUT entry has just completed
busStatus_e w25n_readBBLUTCallback(uint32_t arg)
static busStatus_e w25n_readBBLUTCallback(uint32_t arg)
{
cb_context_t *cb_context = (cb_context_t *)arg;
flashDevice_t *fdevice = cb_context->fdevice;
@ -1027,7 +1027,7 @@ busStatus_e w25n_readBBLUTCallback(uint32_t arg)
return BUS_READY; // All done
}
void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
LOCAL_UNUSED_FUNCTION static void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
{
cb_context_t cb_context;
uint8_t in[4];
@ -1078,7 +1078,7 @@ void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
#endif
}
void w25n_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
LOCAL_UNUSED_FUNCTION static void w25n_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
{
w25n_waitForReady(fdevice);

View file

@ -228,7 +228,7 @@ static void w25q128fv_deviceReset(flashDevice_t *fdevice)
#endif
}
MMFLASH_CODE bool w25q128fv_isReady(flashDevice_t *fdevice)
static MMFLASH_CODE bool w25q128fv_isReady(flashDevice_t *fdevice)
{
uint8_t status = w25q128fv_readRegister(&fdevice->io, W25Q128FV_INSTRUCTION_READ_STATUS1_REG);
@ -246,7 +246,7 @@ MMFLASH_CODE static bool w25q128fv_isWritable(flashDevice_t *fdevice)
return writable;
}
MMFLASH_CODE bool w25q128fv_hasTimedOut(flashDevice_t *fdevice)
static MMFLASH_CODE bool w25q128fv_hasTimedOut(flashDevice_t *fdevice)
{
uint32_t nowMs = microsISR() / 1000;
if (cmp32(nowMs, fdevice->timeoutAt) >= 0) {
@ -335,7 +335,7 @@ MMFLASH_CODE_NOINLINE bool w25q128fv_identify(flashDevice_t *fdevice, uint32_t j
return true;
}
void w25q128fv_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
static void w25q128fv_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
{
if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) {
return;
@ -437,7 +437,7 @@ MMFLASH_CODE static void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t
w25q128fv_pageProgramFinish(fdevice);
}
MMFLASH_CODE void w25q128fv_flush(flashDevice_t *fdevice)
static MMFLASH_CODE void w25q128fv_flush(flashDevice_t *fdevice)
{
UNUSED(fdevice);
}
@ -473,7 +473,7 @@ MMFLASH_CODE static int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t add
return length;
}
const flashGeometry_t* w25q128fv_getGeometry(flashDevice_t *fdevice)
static const flashGeometry_t* w25q128fv_getGeometry(flashDevice_t *fdevice)
{
return &fdevice->geometry;
}

View file

@ -48,10 +48,12 @@ uint16_t IO_Pin(IO_t io)
return ioRec->pin;
}
#if defined(STM32F4) || defined(APM32F4)
int IO_EXTI_PortSourceGPIO(IO_t io)
{
return IO_GPIOPortIdx(io);
}
#endif
int IO_GPIO_PortSource(IO_t io)
{
@ -67,10 +69,12 @@ int IO_GPIOPinIdx(IO_t io)
return 31 - __builtin_clz(IO_Pin(io));
}
#if defined(STM32F4) || defined(APM32F4)
int IO_EXTI_PinSource(IO_t io)
{
return IO_GPIOPinIdx(io);
}
#endif
int IO_GPIO_PinSource(IO_t io)
{

View file

@ -23,10 +23,12 @@
#include "pg/pg_ids.h"
#include "drivers/io.h"
#include "io_impl.h"
#include "drivers/io_impl.h"
#include "light_led.h"
#if !(defined(UNIT_TEST) || defined(USE_VIRTUAL_LED))
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
static IO_t leds[STATUS_LED_NUMBER];
@ -91,3 +93,4 @@ void ledSet(int led, bool on)
const bool inverted = (1 << (led)) & ledInversion;
IOWrite(leds[led], on ? inverted : !inverted);
}
#endif

View file

@ -31,8 +31,6 @@ typedef struct statusLedConfig_s {
uint8_t inversion;
} statusLedConfig_t;
PG_DECLARE(statusLedConfig_t, statusLedConfig);
// Helpful macros
#if defined(UNIT_TEST) || defined(USE_VIRTUAL_LED)
@ -50,6 +48,8 @@ PG_DECLARE(statusLedConfig_t, statusLedConfig);
#else
PG_DECLARE(statusLedConfig_t, statusLedConfig);
#define LED0_TOGGLE ledToggle(0)
#define LED0_OFF ledSet(0, false)
#define LED0_ON ledSet(0, true)

View file

@ -281,7 +281,7 @@ static void max7456ClearLayer(displayPortLayer_e layer)
memset(getLayerBuffer(layer), 0x20, VIDEO_BUFFER_CHARS_PAL);
}
void max7456ReInit(void)
static void max7456ReInit(void)
{
uint8_t srdata = 0;
@ -612,7 +612,7 @@ bool max7456ReInitIfRequired(bool forceStallCheck)
}
// Called in ISR context
busStatus_e max7456_callbackReady(uint32_t arg)
static busStatus_e max7456_callbackReady(uint32_t arg)
{
UNUSED(arg);

View file

@ -28,4 +28,4 @@
struct pinPullUpDownConfig_s;
void pinPullupPulldownInit();
void pinPullupPulldownInit(void);

View file

@ -61,7 +61,7 @@ static IO_t echoIO;
static IO_t triggerIO;
#if !defined(UNIT_TEST)
void hcsr04_extiHandler(extiCallbackRec_t* cb)
static void hcsr04_extiHandler(extiCallbackRec_t* cb)
{
UNUSED(cb);
@ -81,7 +81,7 @@ void hcsr04_extiHandler(extiCallbackRec_t* cb)
}
#endif
void hcsr04_init(rangefinderDev_t *dev)
static void hcsr04_init(rangefinderDev_t *dev)
{
UNUSED(dev);
}
@ -93,7 +93,7 @@ void hcsr04_init(rangefinderDev_t *dev)
* Called periodically by the scheduler
* Measurement reading is done asynchronously, using interrupt
*/
void hcsr04_start_reading(void)
static void hcsr04_start_reading(void)
{
#if !defined(UNIT_TEST)
IOHi(triggerIO);
@ -102,7 +102,7 @@ void hcsr04_start_reading(void)
#endif
}
void hcsr04_update(rangefinderDev_t *dev)
static void hcsr04_update(rangefinderDev_t *dev)
{
UNUSED(dev);
@ -136,7 +136,7 @@ void hcsr04_update(rangefinderDev_t *dev)
/**
* Get the distance that was measured by the last pulse, in centimeters.
*/
int32_t hcsr04_get_distance(rangefinderDev_t *dev)
static int32_t hcsr04_get_distance(rangefinderDev_t *dev)
{
UNUSED(dev);

View file

@ -115,7 +115,7 @@ const MTRangefinderConfig* getMTRangefinderDeviceConf(rangefinderType_e mtRangef
return NULL;
}
const mtRangefinderData_t * getMTRangefinderData(void) {
static const mtRangefinderData_t * getMTRangefinderData(void) {
return &rfSensorData;
}

View file

@ -128,7 +128,7 @@ static void lidarTFSendCommand(void)
}
}
void lidarTFInit(rangefinderDev_t *dev)
static void lidarTFInit(rangefinderDev_t *dev)
{
UNUSED(dev);
@ -136,7 +136,7 @@ void lidarTFInit(rangefinderDev_t *dev)
tfReceivePosition = 0;
}
void lidarTFUpdate(rangefinderDev_t *dev)
static void lidarTFUpdate(rangefinderDev_t *dev)
{
UNUSED(dev);
static timeMs_t lastFrameReceivedMs = 0;
@ -232,7 +232,7 @@ void lidarTFUpdate(rangefinderDev_t *dev)
// Return most recent device output in cm
int32_t lidarTFGetDistance(rangefinderDev_t *dev)
static int32_t lidarTFGetDistance(rangefinderDev_t *dev)
{
UNUSED(dev);

View file

@ -48,12 +48,12 @@ void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len)
rxSpiReadCommandMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, NOP, dpbuffer, len);
}
void cc2500WriteCommand(uint8_t command, uint8_t data)
static void cc2500WriteCommand(uint8_t command, uint8_t data)
{
rxSpiWriteCommand(command, data);
}
void cc2500WriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
static void cc2500WriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
{
rxSpiWriteCommandMulti(command, data, length);
}

View file

@ -125,12 +125,15 @@ void resetPPMDataReceivedState(void)
#define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4
#ifdef DEBUG_PPM_ISR
typedef enum {
SOURCE_OVERFLOW = 0,
SOURCE_EDGE = 1
} eventSource_e;
static void ppmISREvent(eventSource_e source, uint32_t capture);
#ifdef DEBUG_PPM_ISR
typedef struct ppmISREvent_s {
uint32_t capture;
eventSource_e source;
@ -139,7 +142,7 @@ typedef struct ppmISREvent_s {
static ppmISREvent_t ppmEvents[20];
static uint8_t ppmEventIndex = 0;
void ppmISREvent(eventSource_e source, uint32_t capture)
static void ppmISREvent(eventSource_e source, uint32_t capture)
{
ppmEventIndex = (ppmEventIndex + 1) % ARRAYLEN(ppmEvents);
@ -147,7 +150,7 @@ void ppmISREvent(eventSource_e source, uint32_t capture)
ppmEvents[ppmEventIndex].capture = capture;
}
#else
void ppmISREvent(eventSource_e source, uint32_t capture) {}
static void ppmISREvent(eventSource_e source, uint32_t capture) {}
#endif
static void ppmResetDevice(void)
@ -403,7 +406,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
#define FIRST_PWM_PORT 0
#ifdef USE_PWM_OUTPUT
void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
static void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
{
pwmOutputPort_t *motors = pwmGetMotors();
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {

View file

@ -75,7 +75,7 @@ void rxSpiDevicePreinit(const rxSpiConfig_t *rxSpiConfig)
ioPreinitByTag(rxSpiConfig->csnTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
}
void rxSpiExtiHandler(extiCallbackRec_t* callback)
static void rxSpiExtiHandler(extiCallbackRec_t* callback)
{
UNUSED(callback);

View file

@ -35,8 +35,8 @@ extDevice_t *rxSpiGetDevice(void);
void rxSpiDevicePreinit(const struct rxSpiConfig_s *rxSpiConfig);
bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig);
void rxSpiSetNormalSpeedMhz(uint32_t mhz);
void rxSpiNormalSpeed();
void rxSpiStartupSpeed();
void rxSpiNormalSpeed(void);
void rxSpiStartupSpeed(void);
void rxSpiDmaEnable(bool enable);
uint8_t rxSpiTransferByte(uint8_t data);
void rxSpiWriteByte(uint8_t data);

View file

@ -591,7 +591,7 @@ void sx1280GetLastPacketStats(int8_t *rssi, int8_t *snr)
}
}
void sx1280DoFHSS(void)
LOCAL_UNUSED_FUNCTION static void sx1280DoFHSS(void)
{
return;
}

View file

@ -353,7 +353,7 @@ void sx1280SetDioIrqParams(const uint16_t irqMask, const uint16_t dio1Mask, cons
void sx1280ClearIrqStatus(const uint16_t irqMask);
void sx1280GetIrqReason(void);
void sx1280HandleFromTock();
void sx1280HandleFromTock(void);
void sx1280TransmitData(const uint8_t *data, const uint8_t length);
void sx1280ReceiveData(uint8_t *data, const uint8_t length);

View file

@ -48,7 +48,7 @@
uint8_t writeCache[512 * FATFS_BLOCK_CACHE_SIZE] __attribute__ ((aligned (4)));
uint32_t cacheCount = 0;
void cache_write(uint8_t *buffer)
static void cache_write(uint8_t *buffer)
{
if (cacheCount == sizeof(writeCache)) {
// Prevents overflow
@ -58,12 +58,12 @@ void cache_write(uint8_t *buffer)
cacheCount += 512;
}
uint16_t cache_getCount(void)
static uint16_t cache_getCount(void)
{
return (cacheCount / 512);
}
void cache_reset(void)
static void cache_reset(void)
{
cacheCount = 0;
}

View file

@ -112,7 +112,7 @@ static void sdcard_reset(void)
// Called in ISR context
// Wait until idle indicated by a read value of SDCARD_IDLE_TOKEN
busStatus_e sdcard_callbackIdle(uint32_t arg)
static busStatus_e sdcard_callbackIdle(uint32_t arg)
{
sdcard_t *sdcard = (sdcard_t *)arg;
extDevice_t *dev = &sdcard->dev;
@ -135,7 +135,7 @@ busStatus_e sdcard_callbackIdle(uint32_t arg)
// Called in ISR context
// Wait until idle is no longer indicated by a read value of SDCARD_IDLE_TOKEN
busStatus_e sdcard_callbackNotIdle(uint32_t arg)
static busStatus_e sdcard_callbackNotIdle(uint32_t arg)
{
sdcard_t *sdcard = (sdcard_t *)arg;
extDevice_t *dev = &sdcard->dev;
@ -340,7 +340,7 @@ typedef enum {
/// Called in ISR context
// Wait until the arrival of the SDCARD_SINGLE_BLOCK_READ_START_TOKEN token
busStatus_e sdcard_callbackNotIdleDataBlock(uint32_t arg)
static busStatus_e sdcard_callbackNotIdleDataBlock(uint32_t arg)
{
sdcard_t *sdcard = (sdcard_t *)arg;
extDevice_t *dev = &sdcard->dev;
@ -536,7 +536,7 @@ static bool sdcard_checkInitDone(void)
return status == 0x00;
}
void sdcardSpi_preinit(const sdcardConfig_t *config)
static void sdcardSpi_preinit(const sdcardConfig_t *config)
{
ioPreinitByTag(config->chipSelectTag, IOCFG_IPU, PREINIT_PIN_STATE_HIGH);
}

View file

@ -30,6 +30,6 @@ typedef enum {
#define SDIODEV_COUNT 2
#if defined(STM32H7)
void sdioPinConfigure();
void sdioPinConfigure(void);
void SDIO_GPIO_Init(void);
#endif

View file

@ -73,7 +73,7 @@ typedef enum {
#define CTRL_LINE_STATE_RTS (1 << 1)
typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app
typedef void (*serialIdleCallbackPtr)();
typedef void (*serialIdleCallbackPtr)(void);
typedef struct serialPort_s {

View file

@ -23,6 +23,9 @@
#include <stdbool.h>
#include "drivers/resource.h"
#include "io/serial.h"
/*
* common functions related to serial port implementation
*/

View file

@ -195,7 +195,7 @@ static void resetBuffers(softSerial_t *softSerial)
softSerial->port.txBufferHead = 0;
}
softSerial_t* softSerialFromIdentifier(serialPortIdentifier_e identifier)
static softSerial_t* softSerialFromIdentifier(serialPortIdentifier_e identifier)
{
if (identifier >= SERIAL_PORT_SOFTSERIAL_FIRST && identifier < SERIAL_PORT_SOFTSERIAL_FIRST + SERIAL_SOFTSERIAL_COUNT) {
return &softSerialPorts[identifier - SERIAL_PORT_SOFTSERIAL_FIRST];
@ -330,7 +330,7 @@ serialPort_t *softSerialOpen(serialPortIdentifier_e identifier, serialReceiveCal
* Serial Engine
*/
void processTxState(softSerial_t *softSerial)
static void processTxState(softSerial_t *softSerial)
{
if (!softSerial->isTransmittingData) {
if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) {
@ -387,7 +387,7 @@ enum {
LEADING
};
void applyChangedBits(softSerial_t *softSerial)
static void applyChangedBits(softSerial_t *softSerial)
{
if (softSerial->rxEdge == TRAILING) {
for (unsigned bitToSet = softSerial->rxLastLeadingEdgeAtBitIndex; bitToSet < softSerial->rxBitIndex; bitToSet++) {
@ -396,7 +396,7 @@ void applyChangedBits(softSerial_t *softSerial)
}
}
void prepareForNextRxByte(softSerial_t *softSerial)
static void prepareForNextRxByte(softSerial_t *softSerial)
{
// prepare for next byte
softSerial->rxBitIndex = 0;
@ -411,7 +411,7 @@ void prepareForNextRxByte(softSerial_t *softSerial)
#define STOP_BIT_MASK (1 << 0)
#define START_BIT_MASK (1 << (RX_TOTAL_BITS - 1))
void extractAndStoreRxByte(softSerial_t *softSerial)
static void extractAndStoreRxByte(softSerial_t *softSerial)
{
if ((softSerial->port.mode & MODE_RX) == 0) {
return;
@ -435,7 +435,7 @@ void extractAndStoreRxByte(softSerial_t *softSerial)
}
}
void processRxState(softSerial_t *softSerial)
static void processRxState(softSerial_t *softSerial)
{
if (softSerial->isSearchingForStartBit) {
return;
@ -597,7 +597,7 @@ void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate)
serialTimerConfigureTimebase(softSerial->timerHardware, baudRate);
}
void softSerialSetMode(serialPort_t *instance, portMode_e mode)
static void softSerialSetMode(serialPort_t *instance, portMode_e mode)
{
instance->mode = mode;
}

View file

@ -158,7 +158,7 @@ serialPort_t *serTcpOpen(serialPortIdentifier_e identifier, serialReceiveCallbac
return (serialPort_t *)s;
}
uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
static uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
{
tcpPort_t *s = (tcpPort_t*)instance;
uint32_t count;
@ -173,7 +173,7 @@ uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
return count;
}
uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
static uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
{
tcpPort_t *s = (tcpPort_t*)instance;
uint32_t bytesUsed;
@ -190,7 +190,7 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
return bytesFree;
}
bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
static bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
{
tcpPort_t *s = (tcpPort_t *)instance;
pthread_mutex_lock(&s->txLock);
@ -199,7 +199,7 @@ bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
return isEmpty;
}
uint8_t tcpRead(serialPort_t *instance)
static uint8_t tcpRead(serialPort_t *instance)
{
uint8_t ch;
tcpPort_t *s = (tcpPort_t *)instance;
@ -216,7 +216,7 @@ uint8_t tcpRead(serialPort_t *instance)
return ch;
}
void tcpWrite(serialPort_t *instance, uint8_t ch)
static void tcpWrite(serialPort_t *instance, uint8_t ch)
{
tcpPort_t *s = (tcpPort_t *)instance;
pthread_mutex_lock(&s->txLock);

View file

@ -31,6 +31,8 @@
#include "drivers/time.h"
#include "drivers/vtx_rtc6705.h"
#include "vtx_rtc6705_soft_spi.h"
#define DP_5G_MASK 0x7000
#define PA5G_BS_MASK 0x0E00
#define PA5G_PW_MASK 0x0180

View file

@ -159,7 +159,7 @@ void vtxTableConfigClearChannels(vtxTableConfig_t *config, int band, int channel
}
// Clear a channel name for "channel"
void vtxTableConfigClearChannelNames(vtxTableConfig_t *config, int channel)
static void vtxTableConfigClearChannelNames(vtxTableConfig_t *config, int channel)
{
tfp_sprintf(config->channelNames[channel], "%d", channel + 1);
}

View file

@ -25,6 +25,7 @@
#if defined(USE_BOARD_INFO)
#include "pg/board.h"
#include "board_info.h"
#if !defined(BOARD_NAME)
static bool boardInformationSet = false;

View file

@ -22,16 +22,16 @@
void initBoardInformation(void);
char *getBoardName(void);
char *getManufacturerId(void);
const char *getBoardName(void);
const char *getManufacturerId(void);
bool boardInformationIsSet(void);
bool setBoardName(char *newBoardName);
bool setManufacturerId(char *newManufacturerId);
bool setBoardName(const char *newBoardName);
bool setManufacturerId(const char *newManufacturerId);
bool persistBoardInformation(void);
uint8_t * getSignature(void);
const uint8_t * getSignature(void);
bool signatureIsSet(void);
bool setSignature(uint8_t *newSignature);
bool setSignature(const uint8_t *newSignature);
bool persistSignature(void);

View file

@ -197,7 +197,7 @@ static bool isCalibrating(void)
}
#ifdef USE_LAUNCH_CONTROL
bool canUseLaunchControl(void)
static bool canUseLaunchControl(void)
{
if (!isFixedWing()
&& !isUsingSticksForArming() // require switch arming for safety
@ -212,7 +212,7 @@ bool canUseLaunchControl(void)
#endif
#ifdef USE_DSHOT
void setMotorSpinDirection(uint8_t spinDirection)
static void setMotorSpinDirection(uint8_t spinDirection)
{
if (isMotorProtocolDshot() && !featureIsEnabled(FEATURE_3D)) {
dshotCommandWrite(ALL_MOTORS, getMotorCount(), spinDirection, DSHOT_CMD_TYPE_INLINE);

View file

@ -91,10 +91,10 @@ int8_t calculateThrottlePercent(void);
uint8_t calculateThrottlePercentAbs(void);
bool areSticksActive(uint8_t stickPercentLimit);
void runawayTakeoffTemporaryDisable(uint8_t disableFlag);
bool wasThrottleRaised();
bool wasThrottleRaised(void);
timeUs_t getLastDisarmTimeUs(void);
bool isTryingToArm();
void resetTryingToArm();
bool isTryingToArm(void);
void resetTryingToArm(void);
void subTaskTelemetryPollSensors(timeUs_t currentTimeUs);

View file

@ -69,7 +69,7 @@ void gpsLapTimerStartSetGate(void)
gpsLapTimerData.numberOfSetReadings = 0;
}
void gpsLapTimerProcessSettingGate(void)
static void gpsLapTimerProcessSettingGate(void)
{
if (gpsLapTimerData.numberOfSetReadings < MAX_GATE_SET_READINGS){
gateSetLatReadings += gpsSol.llh.lat;

View file

@ -166,7 +166,7 @@ STATIC_ASSERT(CONTROL_RATE_CONFIG_RATE_LIMIT_MAX <= (uint16_t)SETPOINT_RATE_LIMI
#define RC_RATE_INCREMENTAL 14.54f
float applyBetaflightRates(const int axis, float rcCommandf, const float rcCommandfAbs)
static float applyBetaflightRates(const int axis, float rcCommandf, const float rcCommandfAbs)
{
if (currentControlRateProfile->rcExpo[axis]) {
const float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
@ -186,7 +186,7 @@ float applyBetaflightRates(const int axis, float rcCommandf, const float rcComma
return angleRate;
}
float applyRaceFlightRates(const int axis, float rcCommandf, const float rcCommandfAbs)
static float applyRaceFlightRates(const int axis, float rcCommandf, const float rcCommandfAbs)
{
// -1.0 to 1.0 ranged and curved
rcCommandf = ((1.0f + 0.01f * currentControlRateProfile->rcExpo[axis] * (rcCommandf * rcCommandf - 1.0f)) * rcCommandf);
@ -197,7 +197,7 @@ float applyRaceFlightRates(const int axis, float rcCommandf, const float rcComma
return angleRate;
}
float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs)
static float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs)
{
const float rcCurvef = currentControlRateProfile->rcExpo[axis] / 100.0f;
@ -208,7 +208,7 @@ float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs
return kissAngle;
}
float applyActualRates(const int axis, float rcCommandf, const float rcCommandfAbs)
static float applyActualRates(const int axis, float rcCommandf, const float rcCommandfAbs)
{
float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
expof = rcCommandfAbs * (power5(rcCommandf) * expof + rcCommandf * (1 - expof));
@ -220,7 +220,7 @@ float applyActualRates(const int axis, float rcCommandf, const float rcCommandfA
return angleRate;
}
float applyQuickRates(const int axis, float rcCommandf, const float rcCommandfAbs)
static float applyQuickRates(const int axis, float rcCommandf, const float rcCommandfAbs)
{
const uint16_t rcRate = currentControlRateProfile->rcRates[axis] * 2;
const uint16_t maxDPS = MAX(currentControlRateProfile->rates[axis] * 10, rcRate);
@ -322,7 +322,7 @@ bool getRxRateValid(void)
// Initialize or update the filters base on either the manually selected cutoff, or
// the auto-calculated cutoff frequency based on detected rx frame rate.
FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothingData)
static FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothingData)
{
// in auto mode, calculate the RC smoothing cutoff from the smoothed Rx link frequency
const uint16_t oldSetpointCutoff = smoothingData->setpointCutoffFrequency;
@ -518,7 +518,7 @@ static FAST_CODE void processRcSmoothingFilter(void)
#endif // USE_RC_SMOOTHING_FILTER
#ifdef USE_FEEDFORWARD
FAST_CODE_NOINLINE void calculateFeedforward(const pidRuntime_t *pid, flight_dynamics_index_t axis)
static FAST_CODE_NOINLINE void calculateFeedforward(const pidRuntime_t *pid, flight_dynamics_index_t axis)
{
const float rxInterval = currentRxIntervalUs * 1e-6f; // seconds
float rxRate = currentRxRateHz; // 1e6f / currentRxIntervalUs;

View file

@ -139,7 +139,7 @@ PG_DECLARE(armingConfig_t, armingConfig);
bool areUsingSticksToArm(void);
throttleStatus_e calculateThrottleStatus(void);
void processRcStickPositions();
void processRcStickPositions(void);
bool isUsingSticksForArming(void);

View file

@ -99,7 +99,7 @@ bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range)
* T F - all previous AND macs active, no previous active OR macs
* T T - at least 1 previous inactive AND mac, no previous active OR macs
*/
void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask, bool bActive)
static void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask, bool bActive)
{
if (bitArrayGet(andMask, mac->modeId) || !bitArrayGet(newMask, mac->modeId)) {
bool bAnd = mac->modeLogic == MODELOGIC_AND;
@ -118,7 +118,7 @@ void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMa
}
}
void updateMasksForStickyModes(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask)
static void updateMasksForStickyModes(const modeActivationCondition_t *mac, boxBitmask_t *andMask, boxBitmask_t *newMask)
{
if (IS_RC_MODE_ACTIVE(mac->modeId)) {
bitArrayClr(andMask, mac->modeId);

View file

@ -289,7 +289,7 @@ static void taskCalculateAltitude(timeUs_t currentTimeUs)
#endif // USE_BARO || USE_GPS
#if defined(USE_RANGEFINDER)
void taskUpdateRangefinder(timeUs_t currentTimeUs)
static void taskUpdateRangefinder(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
@ -304,7 +304,7 @@ void taskUpdateRangefinder(timeUs_t currentTimeUs)
#endif
#ifdef USE_OPTICALFLOW
void taskUpdateOpticalflow(timeUs_t currentTimeUs)
static void taskUpdateOpticalflow(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);

View file

@ -26,5 +26,5 @@ void tasksInitData(void);
void tasksInit(void);
task_t *getTask(unsigned taskId);
bool taskUpdateRxMainInProgress();
bool taskUpdateRxMainInProgress(void);

View file

@ -52,7 +52,7 @@ typedef struct {
altHoldState_t altHold;
void altHoldReset(void)
static void altHoldReset(void)
{
resetAltitudeControl();
altHold.targetAltitudeCm = getAltitudeCm();
@ -68,7 +68,7 @@ void altHoldInit(void)
altHoldReset();
}
void altHoldProcessTransitions(void) {
static void altHoldProcessTransitions(void) {
if (FLIGHT_MODE(ALT_HOLD_MODE)) {
if (!altHold.isActive) {
@ -90,7 +90,7 @@ void altHoldProcessTransitions(void) {
// user throttle must be not more than half way out from hover for a stable hold
}
void altHoldUpdateTargetAltitude(void)
static void altHoldUpdateTargetAltitude(void)
{
// User can adjust the target altitude with throttle, but only when
// - throttle is outside deadband, and
@ -133,7 +133,7 @@ void altHoldUpdateTargetAltitude(void)
}
}
void altHoldUpdate(void)
static void altHoldUpdate(void)
{
// check if the user has changed the target altitude using sticks
if (altHoldConfig()->alt_hold_adjust_rate) {

View file

@ -39,7 +39,7 @@
#include "alt_hold.h"
void altHoldReset(void)
LOCAL_UNUSED_FUNCTION static void altHoldReset(void)
{
}

View file

@ -98,7 +98,7 @@ static void resetEFAxisFilters(efPidAxis_t* efAxis, const float vaGain)
pt1FilterInit(&efAxis->accelerationLpf, vaGain);
}
void resetEFAxisParams(efPidAxis_t *efAxis, const float vaGain)
static void resetEFAxisParams(efPidAxis_t *efAxis, const float vaGain)
{
// at start only
resetEFAxisFilters(efAxis, vaGain);
@ -223,7 +223,7 @@ void setSticksActiveStatus(bool areSticksActive)
ap.sticksActive = areSticksActive;
}
void setTargetLocationByAxis(const gpsLocation_t* newTargetLocation, axisEF_e efAxisIdx)
static void setTargetLocationByAxis(const gpsLocation_t* newTargetLocation, axisEF_e efAxisIdx)
// not used at present but needed by upcoming GPS code
{
if (efAxisIdx == LON) {

View file

@ -219,7 +219,7 @@ void failsafeCheckDataFailurePeriod(void)
}
}
uint32_t failsafeFailurePeriodMs(void)
LOCAL_UNUSED_FUNCTION static uint32_t failsafeFailurePeriodMs(void)
{
return failsafeState.rxDataFailurePeriod;
}

View file

@ -617,7 +617,7 @@ static bool checkGPSRescueIsAvailable(void)
return result;
}
void disarmOnImpact(void)
static void disarmOnImpact(void)
{
if (acc.accMagnitude > rescueState.intent.disarmThreshold) {
setArmingDisabled(ARMING_DISABLED_ARM_SWITCH);
@ -626,7 +626,7 @@ void disarmOnImpact(void)
}
}
void descend(bool newGpsData)
static void descend(bool newGpsData)
{
if (newGpsData) {
// consider landing area to be a circle half landing height around home, to avoid overshooting home point
@ -672,7 +672,7 @@ void descend(bool newGpsData)
rescueState.intent.targetAltitudeCm -= altitudeStepCm;
}
void initialiseRescueValues (void)
static void initialiseRescueValues (void)
{
rescueState.intent.secondsFailing = 0; // reset the sanity check timer
rescueState.intent.yawAttenuator = 0.0f; // no yaw in the climb

View file

@ -854,7 +854,7 @@ bool imuQuaternionHeadfreeOffsetSet(void)
}
}
void imuQuaternionMultiplication(quaternion_t *q1, quaternion_t *q2, quaternion_t *result)
static void imuQuaternionMultiplication(quaternion_t *q1, quaternion_t *q2, quaternion_t *result)
{
const float A = (q1->w + q1->x) * (q2->w + q2->x);
const float B = (q1->z - q1->y) * (q2->y - q2->z);

View file

@ -396,7 +396,7 @@ void mixerResetRpmLimiter(void)
// Create a custom mixer for launch control based on the current settings
// but disable the front motors. We don't care about roll or yaw because they
// are limited in the PID controller.
void loadLaunchControlMixer(void)
static void loadLaunchControlMixer(void)
{
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
mixerRuntime.launchControlMixer[i] = mixerRuntime.currentMixer[i];

View file

@ -416,7 +416,7 @@ static float wingAdjustSetpoint(float currentPidSetpoint, int axis)
#endif // USE_WING
}
float getTpaFactorClassic(float tpaArgument)
static float getTpaFactorClassic(float tpaArgument)
{
static bool isTpaLowFaded = false;
bool isThrottlePastTpaLowBreakpoint = (tpaArgument >= pidRuntime.tpaLowBreakpoint || pidRuntime.tpaLowBreakpoint <= 0.01f);

View file

@ -584,7 +584,7 @@ float pidCompensateThrustLinearization(float throttle);
#ifdef USE_AIRMODE_LPF
void pidUpdateAirmodeLpf(float currentOffset);
float pidGetAirmodeThrottleOffset();
float pidGetAirmodeThrottleOffset(void);
#endif
#ifdef UNIT_TEST
@ -602,8 +602,8 @@ float calcHorizonLevelStrength(void);
void dynLpfDTermUpdate(float throttle);
void pidSetItermReset(bool enabled);
float pidGetPreviousSetpoint(int axis);
float pidGetDT();
float pidGetPidFrequency();
float pidGetDT(void);
float pidGetPidFrequency(void);
float dynLpfCutoffFreq(float throttle, uint16_t dynLpfMin, uint16_t dynLpfMax, uint8_t expo);
#ifdef USE_CHIRP

View file

@ -69,7 +69,7 @@ static void pidSetTargetLooptime(uint32_t pidLooptime)
}
#ifdef USE_WING
void tpaSpeedBasicInit(const pidProfile_t *pidProfile)
static void tpaSpeedBasicInit(const pidProfile_t *pidProfile)
{
// basic model assumes prop pitch speed is inf
const float gravityFactor = pidProfile->tpa_speed_basic_gravity / 100.0f;
@ -82,7 +82,7 @@ void tpaSpeedBasicInit(const pidProfile_t *pidProfile)
pidRuntime.tpaSpeed.inversePropMaxSpeed = 0.0f;
}
void tpaSpeedAdvancedInit(const pidProfile_t *pidProfile)
static void tpaSpeedAdvancedInit(const pidProfile_t *pidProfile)
{
// Advanced model uses prop pitch speed, and is quite limited when craft speed is far above prop pitch speed.
pidRuntime.tpaSpeed.twr = (float)pidProfile->tpa_speed_adv_thrust / (float)pidProfile->tpa_speed_adv_mass;
@ -109,7 +109,7 @@ void tpaSpeedAdvancedInit(const pidProfile_t *pidProfile)
UNUSED(pidProfile);
}
void tpaSpeedInit(const pidProfile_t *pidProfile)
static void tpaSpeedInit(const pidProfile_t *pidProfile)
{
pidRuntime.tpaSpeed.speed = 0.0f;
pidRuntime.tpaSpeed.maxVoltage = pidProfile->tpa_speed_max_voltage / 100.0f;
@ -334,7 +334,7 @@ void pidInitFilters(const pidProfile_t *pidProfile)
}
#ifdef USE_ADVANCED_TPA
float tpaCurveHyperbolicFunction(float x, void *args)
static float tpaCurveHyperbolicFunction(float x, void *args)
{
const pidProfile_t *pidProfile = (const pidProfile_t*)args;
@ -356,13 +356,13 @@ float tpaCurveHyperbolicFunction(float x, void *args)
return pidThr0 / divisor;
}
void tpaCurveHyperbolicInit(const pidProfile_t *pidProfile)
static void tpaCurveHyperbolicInit(const pidProfile_t *pidProfile)
{
pwlInitialize(&pidRuntime.tpaCurvePwl, pidRuntime.tpaCurvePwl_yValues, TPA_CURVE_PWL_SIZE, 0.0f, 1.0f);
pwlFill(&pidRuntime.tpaCurvePwl, tpaCurveHyperbolicFunction, (void*)pidProfile);
}
void tpaCurveInit(const pidProfile_t *pidProfile)
static void tpaCurveInit(const pidProfile_t *pidProfile)
{
pidRuntime.tpaCurveType = pidProfile->tpa_curve_type;
switch (pidRuntime.tpaCurveType) {

View file

@ -55,7 +55,7 @@ void posHoldInit(void)
posHold.useStickAdjustment = posHoldConfig()->pos_hold_deadband;
}
void posHoldCheckSticks(void)
static void posHoldCheckSticks(void)
{
// if failsafe is active, eg landing mode, don't update the original start point
if (!failsafeIsActive() && posHold.useStickAdjustment) {
@ -64,7 +64,7 @@ void posHoldCheckSticks(void)
}
}
bool sensorsOk(void)
static bool sensorsOk(void)
{
if (!STATE(GPS_FIX)) {
return false;

View file

@ -204,7 +204,7 @@ const mixerRules_t servoMixers[] = {
{ 0, NULL },
};
int16_t determineServoMiddleOrForwardFromChannel(servoIndex_e servoIndex)
static int16_t determineServoMiddleOrForwardFromChannel(servoIndex_e servoIndex)
{
const uint8_t channelToForwardFrom = servoParams(servoIndex)->forwardFromChannel;

View file

@ -131,7 +131,7 @@ static void resetDisplay(void)
dashboardPresent = ug2864hsweg01InitI2C(dev);
}
void LCDprint(uint8_t i)
static void LCDprint(uint8_t i)
{
i2c_OLED_send_char(dev, i);
}
@ -628,7 +628,7 @@ static const pageEntry_t pages[PAGE_COUNT] = {
#endif
};
void dashboardSetPage(pageId_e pageId)
static void dashboardSetPage(pageId_e pageId)
{
for (int i = 0; i < PAGE_COUNT; i++) {
const pageEntry_t *candidatePage = &pages[i];

View file

@ -30,6 +30,8 @@
#include "cms/cms.h"
#include "telemetry/hott.h"
#include "displayport_hott.h"
displayPort_t hottDisplayPort;
static bool hottDrawScreen(displayPort_t *displayPort)

View file

@ -21,6 +21,6 @@
#pragma once
#include "drivers/display.h"
void hottDisplayportRegister();
void hottCmsOpen();
void hottDisplayportRegister(void);
void hottCmsOpen(void);
void hottSetCmsKey(uint8_t hottKey, bool esc);

View file

@ -185,7 +185,7 @@ static bool checkReady(displayPort_t *displayPort, bool rescan)
return true;
}
void setBackgroundType(displayPort_t *displayPort, displayPortBackground_e backgroundType)
static void setBackgroundType(displayPort_t *displayPort, displayPortBackground_e backgroundType)
{
UNUSED(displayPort);
max7456SetBackgroundType(backgroundType);

View file

@ -28,6 +28,8 @@
#include "drivers/display.h"
#include "drivers/display_ug2864hsweg01.h"
#include "displayport_oled.h"
static displayPort_t oledDisplayPort;
static int oledGrab(displayPort_t *displayPort)

View file

@ -282,7 +282,7 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta)
*
* Returns the number of bytes written
*/
void flashfsWriteCallback(uint32_t arg)
static void flashfsWriteCallback(uint32_t arg)
{
// Advance the cursor in the file system to match the bytes we wrote
flashfsSetTailAddress(tailAddress + arg);

View file

@ -958,7 +958,7 @@ static void setSatInfoMessageRate(uint8_t divisor)
#endif // USE_GPS_UBLOX
#ifdef USE_GPS_NMEA
void gpsConfigureNmea(void)
static void gpsConfigureNmea(void)
{
// minimal support for NMEA, we only:
// - set the FC's GPS port to the user's configured rate, and
@ -1031,7 +1031,7 @@ void gpsConfigureNmea(void)
#ifdef USE_GPS_UBLOX
void gpsConfigureUblox(void)
static void gpsConfigureUblox(void)
{
// Wait until GPS transmit buffer is empty
@ -1302,7 +1302,7 @@ void gpsConfigureUblox(void)
}
#endif // USE_GPS_UBLOX
void gpsConfigureHardware(void)
static void gpsConfigureHardware(void)
{
switch (gpsConfig()->provider) {
case GPS_NMEA:
@ -2628,7 +2628,7 @@ void GPS_distance_cm_bearing(const gpsLocation_t *from, const gpsLocation_t* to,
}
}
void GPS_calculateDistanceAndDirectionToHome(void)
static void GPS_calculateDistanceAndDirectionToHome(void)
{
if (STATE(GPS_FIX_HOME)) {
uint32_t dist;

View file

@ -286,7 +286,7 @@ enum ledBarIds {
};
static uint8_t ledBarStates[LED_BAR_COUNT] = {0};
void updateLedBars(void)
static void updateLedBars(void)
{
memset(ledBarStates, 0, sizeof(ledBarStates));
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
@ -1193,7 +1193,7 @@ static applyLayerFn_timed* layerTable[] = {
[timRing] = &applyLedThrustRingLayer
};
bool isOverlayTypeUsed(ledOverlayId_e overlayType)
static bool isOverlayTypeUsed(ledOverlayId_e overlayType)
{
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
const ledConfig_t *ledConfig = &ledStripStatusModeConfig()->ledConfigs[ledIndex];

View file

@ -44,12 +44,12 @@ void pidAudioInit(void)
audioSetupIO();
}
void pidAudioStart(void)
static void pidAudioStart(void)
{
audioGenerateWhiteNoise();
}
void pidAudioStop(void)
static void pidAudioStop(void)
{
audioSilence();
}

View file

@ -172,4 +172,4 @@ void runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device, rcdev
void runcamDeviceSendAttitude(runcamDevice_t *device);
runcamDeviceRequest_t* rcdeviceGetRequest();
runcamDeviceRequest_t* rcdeviceGetRequest(void);

View file

@ -338,7 +338,7 @@ serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identi
return NULL;
}
serialPortUsage_t *findSerialPortUsageByPort(const serialPort_t *serialPort)
static serialPortUsage_t *findSerialPortUsageByPort(const serialPort_t *serialPort)
{
for (serialPortUsage_t* usage = serialPortUsageList; usage < ARRAYEND(serialPortUsageList); usage++) {
if (usage->serialPort == serialPort) {

View file

@ -184,7 +184,6 @@ const serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function
portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function);
bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);
void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier);
int findSerialPortIndexByIdentifier(serialPortIdentifier_e identifier);
serialPortIdentifier_e findSerialPortByName(const char* portName, int (*cmp)(const char *portName, const char *candidate));

View file

@ -318,7 +318,7 @@ void esc4wayRelease(void)
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE. */
uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data)
static uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data)
{
int i;

View file

@ -25,6 +25,8 @@
#include "platform.h"
#include "drivers/serial_impl.h"
#include "io/serial.h"
// convert identifier into port type

View file

@ -50,7 +50,7 @@ static uint16_t spek_fade_last_sec_count = 0; // Stores the fade count at the la
#endif
// Linear mapping and interpolation function
int32_t map(int32_t x, int32_t in_min, int32_t in_max, int32_t out_min, int32_t out_max)
static int32_t map(int32_t x, int32_t in_min, int32_t in_max, int32_t out_min, int32_t out_max)
{
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}

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