1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

Added void to function declarations/definitions where required

This commit is contained in:
Martin Budden 2017-09-24 09:06:59 +01:00
parent b7988c946e
commit 9a8ff69430
35 changed files with 115 additions and 113 deletions

View file

@ -77,7 +77,7 @@ static struct {
#endif #endif
#ifndef UNIT_TEST #ifndef UNIT_TEST
void blackboxOpen() void blackboxOpen(void)
{ {
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP); serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
if (sharedBlackboxAndMspPort) { if (sharedBlackboxAndMspPort) {
@ -328,7 +328,7 @@ static void blackboxLogFileCreated(afatfsFilePtr_t file)
} }
} }
static void blackboxCreateLogFile() static void blackboxCreateLogFile(void)
{ {
uint32_t remainder = blackboxSDCard.largestLogFileNumber + 1; uint32_t remainder = blackboxSDCard.largestLogFileNumber + 1;
@ -359,7 +359,7 @@ static void blackboxCreateLogFile()
* *
* Keep calling until the function returns true (open is complete). * Keep calling until the function returns true (open is complete).
*/ */
static bool blackboxSDCardBeginLog() static bool blackboxSDCardBeginLog(void)
{ {
fatDirectoryEntry_t *directoryEntry; fatDirectoryEntry_t *directoryEntry;
@ -504,7 +504,7 @@ bool isBlackboxDeviceFull(void)
* Call once every loop iteration in order to maintain the global blackboxHeaderBudget with the number of bytes we can * Call once every loop iteration in order to maintain the global blackboxHeaderBudget with the number of bytes we can
* transmit this iteration. * transmit this iteration.
*/ */
void blackboxReplenishHeaderBudget() void blackboxReplenishHeaderBudget(void)
{ {
int32_t freeSpace; int32_t freeSpace;

View file

@ -68,5 +68,5 @@ bool blackboxDeviceEndLog(bool retainLog);
bool isBlackboxDeviceFull(void); bool isBlackboxDeviceFull(void);
void blackboxReplenishHeaderBudget(); void blackboxReplenishHeaderBudget(void);
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes); blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes);

View file

@ -204,7 +204,7 @@ bool dateTimeSplitFormatted(char *formatted, char **date, char **time)
return false; return false;
} }
bool rtcHasTime() bool rtcHasTime(void)
{ {
return started != 0; return started != 0;
} }
@ -240,4 +240,4 @@ bool rtcSetDateTime(dateTime_t *dt)
{ {
rtcTime_t t = dateTimeToRtcTime(dt); rtcTime_t t = dateTimeToRtcTime(dt);
return rtcSet(&t); return rtcSet(&t);
} }

View file

@ -81,7 +81,7 @@ void dateTimeUTCToLocal(dateTime_t *utcDateTime, dateTime_t *localDateTime);
// be modifed and will become invalid after calling this function. // be modifed and will become invalid after calling this function.
bool dateTimeSplitFormatted(char *formatted, char **date, char **time); bool dateTimeSplitFormatted(char *formatted, char **date, char **time);
bool rtcHasTime(); bool rtcHasTime(void);
bool rtcGet(rtcTime_t *t); bool rtcGet(rtcTime_t *t);
bool rtcSet(rtcTime_t *t); bool rtcSet(rtcTime_t *t);

View file

@ -24,7 +24,7 @@
static uint32_t activeFeaturesLatch = 0; static uint32_t activeFeaturesLatch = 0;
void latchActiveFeatures() void latchActiveFeatures(void)
{ {
activeFeaturesLatch = featureConfig()->enabledFeatures; activeFeaturesLatch = featureConfig()->enabledFeatures;
} }
@ -49,7 +49,7 @@ void featureClear(uint32_t mask)
featureConfigMutable()->enabledFeatures &= ~(mask); featureConfigMutable()->enabledFeatures &= ~(mask);
} }
void featureClearAll() void featureClearAll(void)
{ {
featureConfigMutable()->enabledFeatures = 0; featureConfigMutable()->enabledFeatures = 0;
} }

View file

@ -88,7 +88,7 @@ static void m25p16_performOneByteCommand(uint8_t command)
* The flash requires this write enable command to be sent before commands that would cause * The flash requires this write enable command to be sent before commands that would cause
* a write like program and erase. * a write like program and erase.
*/ */
static void m25p16_writeEnable() static void m25p16_writeEnable(void)
{ {
m25p16_performOneByteCommand(M25P16_INSTRUCTION_WRITE_ENABLE); m25p16_performOneByteCommand(M25P16_INSTRUCTION_WRITE_ENABLE);
@ -96,7 +96,7 @@ static void m25p16_writeEnable()
couldBeBusy = true; couldBeBusy = true;
} }
static uint8_t m25p16_readStatus() static uint8_t m25p16_readStatus(void)
{ {
uint8_t command[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 }; uint8_t command[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
uint8_t in[2]; uint8_t in[2];
@ -110,7 +110,7 @@ static uint8_t m25p16_readStatus()
return in[1]; return in[1];
} }
bool m25p16_isReady() bool m25p16_isReady(void)
{ {
// If couldBeBusy is false, don't bother to poll the flash chip for its status // If couldBeBusy is false, don't bother to poll the flash chip for its status
couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0); couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
@ -135,7 +135,7 @@ bool m25p16_waitForReady(uint32_t timeoutMillis)
* *
* Returns true if we get valid ident, false if something bad happened like there is no M25P16. * Returns true if we get valid ident, false if something bad happened like there is no M25P16.
*/ */
static bool m25p16_readIdentification() static bool m25p16_readIdentification(void)
{ {
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
uint8_t in[4]; uint8_t in[4];
@ -258,7 +258,7 @@ void m25p16_eraseSector(uint32_t address)
DISABLE_M25P16; DISABLE_M25P16;
} }
void m25p16_eraseCompletely() void m25p16_eraseCompletely(void)
{ {
m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS); m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS);
@ -285,7 +285,7 @@ void m25p16_pageProgramContinue(const uint8_t *data, int length)
spiTransfer(M25P16_SPI_INSTANCE, NULL, data, length); spiTransfer(M25P16_SPI_INSTANCE, NULL, data, length);
} }
void m25p16_pageProgramFinish() void m25p16_pageProgramFinish(void)
{ {
DISABLE_M25P16; DISABLE_M25P16;
} }
@ -345,7 +345,7 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length)
* *
* Can be called before calling m25p16_init() (the result would have totalSize = 0). * Can be called before calling m25p16_init() (the result would have totalSize = 0).
*/ */
const flashGeometry_t* m25p16_getGeometry() const flashGeometry_t* m25p16_getGeometry(void)
{ {
return &geometry; return &geometry;
} }

View file

@ -26,17 +26,17 @@
bool m25p16_init(ioTag_t csTag); bool m25p16_init(ioTag_t csTag);
void m25p16_eraseSector(uint32_t address); void m25p16_eraseSector(uint32_t address);
void m25p16_eraseCompletely(); void m25p16_eraseCompletely(void);
void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length); void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length);
void m25p16_pageProgramBegin(uint32_t address); void m25p16_pageProgramBegin(uint32_t address);
void m25p16_pageProgramContinue(const uint8_t *data, int length); void m25p16_pageProgramContinue(const uint8_t *data, int length);
void m25p16_pageProgramFinish(); void m25p16_pageProgramFinish(void);
int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length); int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length);
bool m25p16_isReady(); bool m25p16_isReady(void);
bool m25p16_waitForReady(uint32_t timeoutMillis); bool m25p16_waitForReady(uint32_t timeoutMillis);
const flashGeometry_t* m25p16_getGeometry(); const flashGeometry_t* m25p16_getGeometry(void);

View file

@ -102,7 +102,7 @@ uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
/* /*
* Empty the transmit FIFO buffer. * Empty the transmit FIFO buffer.
*/ */
void NRF24L01_FlushTx() void NRF24L01_FlushTx(void)
{ {
rxSpiWriteByte(FLUSH_TX); rxSpiWriteByte(FLUSH_TX);
} }
@ -110,7 +110,7 @@ void NRF24L01_FlushTx()
/* /*
* Empty the receive FIFO buffer. * Empty the receive FIFO buffer.
*/ */
void NRF24L01_FlushRx() void NRF24L01_FlushRx(void)
{ {
rxSpiWriteByte(FLUSH_RX); rxSpiWriteByte(FLUSH_RX);
} }

View file

@ -174,7 +174,7 @@ uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *ret
} }
#ifdef RX_IRQ_PIN #ifdef RX_IRQ_PIN
bool rxSpiCheckIrq() bool rxSpiCheckIrq(void)
{ {
return !IORead(rxIrqPin); return !IORead(rxIrqPin);
} }

View file

@ -32,5 +32,5 @@ uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data);
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length); uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length);
uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData); uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData);
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length); uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length);
bool rxSpiCheckIrq(); bool rxSpiCheckIrq(void);

View file

@ -610,7 +610,7 @@ static bool sdcard_setBlockLength(uint32_t blockLen)
/* /*
* Returns true if the card is ready to accept read/write commands. * Returns true if the card is ready to accept read/write commands.
*/ */
static bool sdcard_isReady() static bool sdcard_isReady(void)
{ {
return sdcard.state == SDCARD_STATE_READY || sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS; return sdcard.state == SDCARD_STATE_READY || sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
} }
@ -625,7 +625,7 @@ static bool sdcard_isReady()
* the SDCARD_READY state. * the SDCARD_READY state.
* *
*/ */
static sdcardOperationStatus_e sdcard_endWriteBlocks() static sdcardOperationStatus_e sdcard_endWriteBlocks(void)
{ {
sdcard.multiWriteBlocksRemain = 0; sdcard.multiWriteBlocksRemain = 0;

View file

@ -63,11 +63,11 @@ sdcardOperationStatus_e sdcard_writeBlock(uint32_t blockIndex, uint8_t *buffer,
void sdcardInsertionDetectDeinit(void); void sdcardInsertionDetectDeinit(void);
void sdcardInsertionDetectInit(void); void sdcardInsertionDetectInit(void);
bool sdcard_isInserted(); bool sdcard_isInserted(void);
bool sdcard_isInitialized(); bool sdcard_isInitialized(void);
bool sdcard_isFunctional(); bool sdcard_isFunctional(void);
bool sdcard_poll(); bool sdcard_poll(void);
const sdcardMetadata_t* sdcard_getMetadata(); const sdcardMetadata_t* sdcard_getMetadata(void);
void sdcard_setProfilerCallback(sdcard_profilerCallback_c callback); void sdcard_setProfilerCallback(sdcard_profilerCallback_c callback);

View file

@ -154,8 +154,9 @@ static void usbVcpBeginWrite(serialPort_t *instance)
port->buffering = true; port->buffering = true;
} }
uint32_t usbTxBytesFree() static uint32_t usbTxBytesFree(const serialPort_t *instance)
{ {
UNUSED(instance);
return CDC_Send_FreeBytes(); return CDC_Send_FreeBytes();
} }

View file

@ -201,7 +201,7 @@ static void cliPrint(const char *str)
} }
} }
static void cliPrintLinefeed() static void cliPrintLinefeed(void)
{ {
cliPrint("\r\n"); cliPrint("\r\n");
} }

View file

@ -122,7 +122,7 @@ void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
void initEEPROM(void); void initEEPROM(void);
void resetEEPROM(void); void resetEEPROM(void);
void readEEPROM(void); void readEEPROM(void);
void writeEEPROM(); void writeEEPROM(void);
void ensureEEPROMContainsValidData(void); void ensureEEPROMContainsValidData(void);
void saveConfigAndNotify(void); void saveConfigAndNotify(void);

View file

@ -29,10 +29,10 @@ typedef enum disarmReason_e {
DISARM_REASON_COUNT DISARM_REASON_COUNT
} disarmReason_t; } disarmReason_t;
void handleInflightCalibrationStickPosition(); void handleInflightCalibrationStickPosition(void);
void mwDisarm(disarmReason_t disarmReason); void mwDisarm(disarmReason_t disarmReason);
void mwArm(void); void mwArm(void);
disarmReason_t getDisarmReason(void); disarmReason_t getDisarmReason(void);
bool isCalibrating(void); bool isCalibrating(void);

View file

@ -167,7 +167,7 @@ bool failsafeMayRequireNavigationMode(void)
} }
#endif #endif
failsafePhase_e failsafePhase() failsafePhase_e failsafePhase(void)
{ {
return failsafeState.phase; return failsafeState.phase;
} }

View file

@ -151,7 +151,7 @@ void failsafeReset(void);
void failsafeStartMonitoring(void); void failsafeStartMonitoring(void);
void failsafeUpdateState(void); void failsafeUpdateState(void);
failsafePhase_e failsafePhase(); failsafePhase_e failsafePhase(void);
bool failsafeIsMonitoring(void); bool failsafeIsMonitoring(void);
bool failsafeIsActive(void); bool failsafeIsActive(void);
bool failsafeIsReceivingRxData(void); bool failsafeIsReceivingRxData(void);

View file

@ -292,7 +292,7 @@ const mixer_t * findMixer(mixerMode_e mixerMode)
return NULL; return NULL;
} }
uint8_t getMotorCount() uint8_t getMotorCount(void)
{ {
return motorCount; return motorCount;
} }
@ -450,7 +450,7 @@ void stopMotors(void)
delay(50); // give the timers and ESCs a chance to react. delay(50); // give the timers and ESCs a chance to react.
} }
void stopPwmAllMotors() void stopPwmAllMotors(void)
{ {
pwmShutdownPulsesForAllMotors(motorCount); pwmShutdownPulsesForAllMotors(motorCount);
} }

View file

@ -547,7 +547,7 @@ int16_t getHeadingHoldTarget() {
return headingHoldTarget; return headingHoldTarget;
} }
static uint8_t getHeadingHoldState() static uint8_t getHeadingHoldState(void)
{ {
// Don't apply heading hold if overall tilt is greater than maximum angle inclination // Don't apply heading hold if overall tilt is greater than maximum angle inclination
if (calculateCosTiltAngle() < headingHoldCosZLimit) { if (calculateCosTiltAngle() < headingHoldCosZLimit) {

View file

@ -151,7 +151,7 @@ enum {
void updateHeadingHoldTarget(int16_t heading); void updateHeadingHoldTarget(int16_t heading);
void resetHeadingHoldTarget(int16_t heading); void resetHeadingHoldTarget(int16_t heading);
int16_t getHeadingHoldTarget(); int16_t getHeadingHoldTarget(void);
void autotuneUpdateState(void); void autotuneUpdateState(void);
void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRateDps, float reachedRateDps, float pidOutput); void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRateDps, float reachedRateDps, float pidOutput);

View file

@ -543,7 +543,7 @@ static bool afatfs_fileIsBusy(afatfsFilePtr_t file)
* *
* Note that this is the same as the number of clusters in an AFATFS supercluster. * Note that this is the same as the number of clusters in an AFATFS supercluster.
*/ */
static uint32_t afatfs_fatEntriesPerSector() static uint32_t afatfs_fatEntriesPerSector(void)
{ {
return afatfs.filesystemType == FAT_FILESYSTEM_TYPE_FAT32 ? AFATFS_FAT32_FAT_ENTRIES_PER_SECTOR : AFATFS_FAT16_FAT_ENTRIES_PER_SECTOR; return afatfs.filesystemType == FAT_FILESYSTEM_TYPE_FAT32 ? AFATFS_FAT32_FAT_ENTRIES_PER_SECTOR : AFATFS_FAT16_FAT_ENTRIES_PER_SECTOR;
} }
@ -552,7 +552,7 @@ static uint32_t afatfs_fatEntriesPerSector()
* Size of a FAT cluster in bytes * Size of a FAT cluster in bytes
*/ */
ONLY_EXPOSE_FOR_TESTING ONLY_EXPOSE_FOR_TESTING
uint32_t afatfs_clusterSize() uint32_t afatfs_clusterSize(void)
{ {
return afatfs.sectorsPerCluster * AFATFS_SECTOR_SIZE; return afatfs.sectorsPerCluster * AFATFS_SECTOR_SIZE;
} }
@ -810,7 +810,7 @@ static int afatfs_allocateCacheSector(uint32_t sectorIndex)
/** /**
* Attempt to flush dirty cache pages out to the sdcard, returning true if all flushable data has been flushed. * Attempt to flush dirty cache pages out to the sdcard, returning true if all flushable data has been flushed.
*/ */
bool afatfs_flush() bool afatfs_flush(void)
{ {
if (afatfs.cacheDirtyEntries > 0) { if (afatfs.cacheDirtyEntries > 0) {
// Flush the oldest flushable sector // Flush the oldest flushable sector
@ -840,7 +840,7 @@ bool afatfs_flush()
/** /**
* Returns true if either the freefile or the regular cluster pool has been exhausted during a previous write operation. * Returns true if either the freefile or the regular cluster pool has been exhausted during a previous write operation.
*/ */
bool afatfs_isFull() bool afatfs_isFull(void)
{ {
return afatfs.filesystemFull; return afatfs.filesystemFull;
} }
@ -1621,7 +1621,7 @@ static afatfsOperationStatus_e afatfs_appendRegularFreeCluster(afatfsFilePtr_t f
* Size of a AFATFS supercluster in bytes * Size of a AFATFS supercluster in bytes
*/ */
ONLY_EXPOSE_FOR_TESTING ONLY_EXPOSE_FOR_TESTING
uint32_t afatfs_superClusterSize() uint32_t afatfs_superClusterSize(void)
{ {
return afatfs_fatEntriesPerSector() * afatfs_clusterSize(); return afatfs_fatEntriesPerSector() * afatfs_clusterSize();
} }
@ -2367,7 +2367,7 @@ static afatfsOperationStatus_e afatfs_allocateDirectoryEntry(afatfsFilePtr_t dir
* Return a pointer to a free entry in the open files table (a file whose type is "NONE"). You should initialize * Return a pointer to a free entry in the open files table (a file whose type is "NONE"). You should initialize
* the file afterwards with afatfs_initFileHandle(). * the file afterwards with afatfs_initFileHandle().
*/ */
static afatfsFilePtr_t afatfs_allocateFileHandle() static afatfsFilePtr_t afatfs_allocateFileHandle(void)
{ {
for (int i = 0; i < AFATFS_MAX_OPEN_FILES; i++) { for (int i = 0; i < AFATFS_MAX_OPEN_FILES; i++) {
if (afatfs.openFiles[i].type == AFATFS_FILE_TYPE_NONE) { if (afatfs.openFiles[i].type == AFATFS_FILE_TYPE_NONE) {
@ -3214,7 +3214,7 @@ static void afatfs_fileOperationContinue(afatfsFile_t *file)
/** /**
* Check files for pending operations and execute them. * Check files for pending operations and execute them.
*/ */
static void afatfs_fileOperationsPoll() static void afatfs_fileOperationsPoll(void)
{ {
afatfs_fileOperationContinue(&afatfs.currentDirectory); afatfs_fileOperationContinue(&afatfs.currentDirectory);
@ -3232,7 +3232,7 @@ static void afatfs_fileOperationsPoll()
/** /**
* Return the available size of the freefile (used for files in contiguous append mode) * Return the available size of the freefile (used for files in contiguous append mode)
*/ */
uint32_t afatfs_getContiguousFreeSpace() uint32_t afatfs_getContiguousFreeSpace(void)
{ {
return afatfs.freeFile.logicalSize; return afatfs.freeFile.logicalSize;
} }
@ -3241,7 +3241,7 @@ uint32_t afatfs_getContiguousFreeSpace()
* Call to set up the initial state for finding the largest block of free space on the device whose corresponding FAT * Call to set up the initial state for finding the largest block of free space on the device whose corresponding FAT
* sectors are themselves entirely free space (so the free space has dedicated FAT sectors of its own). * sectors are themselves entirely free space (so the free space has dedicated FAT sectors of its own).
*/ */
static void afatfs_findLargestContiguousFreeBlockBegin() static void afatfs_findLargestContiguousFreeBlockBegin(void)
{ {
// The first FAT sector has two reserved entries, so it isn't eligible for this search. Start at the next FAT sector. // The first FAT sector has two reserved entries, so it isn't eligible for this search. Start at the next FAT sector.
afatfs.initState.freeSpaceSearch.candidateStart = afatfs_fatEntriesPerSector(); afatfs.initState.freeSpaceSearch.candidateStart = afatfs_fatEntriesPerSector();
@ -3259,7 +3259,7 @@ static void afatfs_findLargestContiguousFreeBlockBegin()
* AFATFS_OPERATION_SUCCESS - When the search has finished and afatfs.initState.freeSpaceSearch has been updated with the details of the best gap. * AFATFS_OPERATION_SUCCESS - When the search has finished and afatfs.initState.freeSpaceSearch has been updated with the details of the best gap.
* AFATFS_OPERATION_FAILURE - When a read error occured * AFATFS_OPERATION_FAILURE - When a read error occured
*/ */
static afatfsOperationStatus_e afatfs_findLargestContiguousFreeBlockContinue() static afatfsOperationStatus_e afatfs_findLargestContiguousFreeBlockContinue(void)
{ {
afatfsFreeSpaceSearch_t *opState = &afatfs.initState.freeSpaceSearch; afatfsFreeSpaceSearch_t *opState = &afatfs.initState.freeSpaceSearch;
uint32_t fatEntriesPerSector = afatfs_fatEntriesPerSector(); uint32_t fatEntriesPerSector = afatfs_fatEntriesPerSector();
@ -3364,7 +3364,7 @@ static void afatfs_introspecLogCreated(afatfsFile_t *file)
#endif #endif
static void afatfs_initContinue() static void afatfs_initContinue(void)
{ {
#ifdef AFATFS_USE_FREEFILE #ifdef AFATFS_USE_FREEFILE
afatfsOperationStatus_e status; afatfsOperationStatus_e status;
@ -3494,7 +3494,7 @@ static void afatfs_initContinue()
* Check to see if there are any pending operations on the filesystem and perform a little work (without waiting on the * Check to see if there are any pending operations on the filesystem and perform a little work (without waiting on the
* sdcard). You must call this periodically. * sdcard). You must call this periodically.
*/ */
void afatfs_poll() void afatfs_poll(void)
{ {
// Only attempt to continue FS operations if the card is present & ready, otherwise we would just be wasting time // Only attempt to continue FS operations if the card is present & ready, otherwise we would just be wasting time
if (sdcard_poll()) { if (sdcard_poll()) {
@ -3557,17 +3557,17 @@ void afatfs_sdcardProfilerCallback(sdcardBlockOperation_e operation, uint32_t bl
#endif #endif
afatfsFilesystemState_e afatfs_getFilesystemState() afatfsFilesystemState_e afatfs_getFilesystemState(void)
{ {
return afatfs.filesystemState; return afatfs.filesystemState;
} }
afatfsError_e afatfs_getLastError() afatfsError_e afatfs_getLastError(void)
{ {
return afatfs.lastError; return afatfs.lastError;
} }
void afatfs_init() void afatfs_init(void)
{ {
afatfs.filesystemState = AFATFS_FILESYSTEM_STATE_INITIALIZATION; afatfs.filesystemState = AFATFS_FILESYSTEM_STATE_INITIALIZATION;
afatfs.initPhase = AFATFS_INITIALIZATION_READ_MBR; afatfs.initPhase = AFATFS_INITIALIZATION_READ_MBR;
@ -3649,7 +3649,7 @@ bool afatfs_destroy(bool dirty)
/** /**
* Get a pessimistic estimate of the amount of buffer space that we have available to write to immediately. * Get a pessimistic estimate of the amount of buffer space that we have available to write to immediately.
*/ */
uint32_t afatfs_getFreeBufferSpace() uint32_t afatfs_getFreeBufferSpace(void)
{ {
uint32_t result = 0; uint32_t result = 0;
for (int i = 0; i < AFATFS_NUM_CACHE_SECTORS; i++) { for (int i = 0; i < AFATFS_NUM_CACHE_SECTORS; i++) {

View file

@ -58,7 +58,7 @@ typedef enum {
} afatfsSeek_e; } afatfsSeek_e;
typedef void (*afatfsFileCallback_t)(afatfsFilePtr_t file); typedef void (*afatfsFileCallback_t)(afatfsFilePtr_t file);
typedef void (*afatfsCallback_t)(); typedef void (*afatfsCallback_t)(void);
bool afatfs_fopen(const char *filename, const char *mode, afatfsFileCallback_t complete); bool afatfs_fopen(const char *filename, const char *mode, afatfsFileCallback_t complete);
bool afatfs_ftruncate(afatfsFilePtr_t file, afatfsFileCallback_t callback); bool afatfs_ftruncate(afatfsFilePtr_t file, afatfsFileCallback_t callback);
@ -79,14 +79,14 @@ void afatfs_findFirst(afatfsFilePtr_t directory, afatfsFinder_t *finder);
afatfsOperationStatus_e afatfs_findNext(afatfsFilePtr_t directory, afatfsFinder_t *finder, fatDirectoryEntry_t **dirEntry); afatfsOperationStatus_e afatfs_findNext(afatfsFilePtr_t directory, afatfsFinder_t *finder, fatDirectoryEntry_t **dirEntry);
void afatfs_findLast(afatfsFilePtr_t directory); void afatfs_findLast(afatfsFilePtr_t directory);
bool afatfs_flush(); bool afatfs_flush(void);
void afatfs_init(); void afatfs_init(void);
bool afatfs_destroy(bool dirty); bool afatfs_destroy(bool dirty);
void afatfs_poll(); void afatfs_poll(void);
uint32_t afatfs_getFreeBufferSpace(); uint32_t afatfs_getFreeBufferSpace(void);
uint32_t afatfs_getContiguousFreeSpace(); uint32_t afatfs_getContiguousFreeSpace(void);
bool afatfs_isFull(); bool afatfs_isFull(void);
afatfsFilesystemState_e afatfs_getFilesystemState(); afatfsFilesystemState_e afatfs_getFilesystemState(void);
afatfsError_e afatfs_getLastError(); afatfsError_e afatfs_getLastError(void);

View file

@ -50,12 +50,12 @@ static uint8_t bufferHead = 0, bufferTail = 0;
// The position of the buffer's tail in the overall flash address space: // The position of the buffer's tail in the overall flash address space:
static uint32_t tailAddress = 0; static uint32_t tailAddress = 0;
static void flashfsClearBuffer() static void flashfsClearBuffer(void)
{ {
bufferTail = bufferHead = 0; bufferTail = bufferHead = 0;
} }
static bool flashfsBufferIsEmpty() static bool flashfsBufferIsEmpty(void)
{ {
return bufferTail == bufferHead; return bufferTail == bufferHead;
} }
@ -65,7 +65,7 @@ static void flashfsSetTailAddress(uint32_t address)
tailAddress = address; tailAddress = address;
} }
void flashfsEraseCompletely() void flashfsEraseCompletely(void)
{ {
m25p16_eraseCompletely(); m25p16_eraseCompletely();
@ -104,17 +104,17 @@ void flashfsEraseRange(uint32_t start, uint32_t end)
/** /**
* Return true if the flash is not currently occupied with an operation. * Return true if the flash is not currently occupied with an operation.
*/ */
bool flashfsIsReady() bool flashfsIsReady(void)
{ {
return m25p16_isReady(); return m25p16_isReady();
} }
uint32_t flashfsGetSize() uint32_t flashfsGetSize(void)
{ {
return m25p16_getGeometry()->totalSize; return m25p16_getGeometry()->totalSize;
} }
static uint32_t flashfsTransmitBufferUsed() static uint32_t flashfsTransmitBufferUsed(void)
{ {
if (bufferHead >= bufferTail) if (bufferHead >= bufferTail)
return bufferHead - bufferTail; return bufferHead - bufferTail;
@ -125,7 +125,7 @@ static uint32_t flashfsTransmitBufferUsed()
/** /**
* Get the size of the largest single write that flashfs could ever accept without blocking or data loss. * Get the size of the largest single write that flashfs could ever accept without blocking or data loss.
*/ */
uint32_t flashfsGetWriteBufferSize() uint32_t flashfsGetWriteBufferSize(void)
{ {
return FLASHFS_WRITE_BUFFER_USABLE; return FLASHFS_WRITE_BUFFER_USABLE;
} }
@ -133,12 +133,12 @@ uint32_t flashfsGetWriteBufferSize()
/** /**
* Get the number of bytes that can currently be written to flashfs without any blocking or data loss. * Get the number of bytes that can currently be written to flashfs without any blocking or data loss.
*/ */
uint32_t flashfsGetWriteBufferFreeSpace() uint32_t flashfsGetWriteBufferFreeSpace(void)
{ {
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed(); return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
} }
const flashGeometry_t* flashfsGetGeometry() const flashGeometry_t* flashfsGetGeometry(void)
{ {
return m25p16_getGeometry(); return m25p16_getGeometry();
} }
@ -268,7 +268,7 @@ static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t buffer
/** /**
* Get the current offset of the file pointer within the volume. * Get the current offset of the file pointer within the volume.
*/ */
uint32_t flashfsGetOffset() uint32_t flashfsGetOffset(void)
{ {
uint8_t const * buffers[2]; uint8_t const * buffers[2];
uint32_t bufferSizes[2]; uint32_t bufferSizes[2];
@ -303,7 +303,7 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta)
* Returns true if all data in the buffer has been flushed to the device, or false if * Returns true if all data in the buffer has been flushed to the device, or false if
* there is still data to be written (call flush again later). * there is still data to be written (call flush again later).
*/ */
bool flashfsFlushAsync() bool flashfsFlushAsync(void)
{ {
if (flashfsBufferIsEmpty()) { if (flashfsBufferIsEmpty()) {
return true; // Nothing to flush return true; // Nothing to flush
@ -326,7 +326,7 @@ bool flashfsFlushAsync()
* The flash will still be busy some time after this sync completes, but space will * The flash will still be busy some time after this sync completes, but space will
* be freed up to accept more writes in the write buffer. * be freed up to accept more writes in the write buffer.
*/ */
void flashfsFlushSync() void flashfsFlushSync(void)
{ {
if (flashfsBufferIsEmpty()) { if (flashfsBufferIsEmpty()) {
return; // Nothing to flush return; // Nothing to flush
@ -482,7 +482,7 @@ int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len)
/** /**
* Find the offset of the start of the free space on the device (or the size of the device if it is full). * Find the offset of the start of the free space on the device (or the size of the device if it is full).
*/ */
int flashfsIdentifyStartOfFreeSpace() int flashfsIdentifyStartOfFreeSpace(void)
{ {
/* Find the start of the free space on the device by examining the beginning of blocks with a binary search, /* Find the start of the free space on the device by examining the beginning of blocks with a binary search,
* looking for ones that appear to be erased. We can achieve this with good accuracy because an erased block * looking for ones that appear to be erased. We can achieve this with good accuracy because an erased block
@ -551,14 +551,15 @@ int flashfsIdentifyStartOfFreeSpace()
/** /**
* Returns true if the file pointer is at the end of the device. * Returns true if the file pointer is at the end of the device.
*/ */
bool flashfsIsEOF() { bool flashfsIsEOF(void)
{
return tailAddress >= flashfsGetSize(); return tailAddress >= flashfsGetSize();
} }
/** /**
* Call after initializing the flash chip in order to set up the filesystem. * Call after initializing the flash chip in order to set up the filesystem.
*/ */
void flashfsInit() void flashfsInit(void)
{ {
// If we have a flash chip present at all // If we have a flash chip present at all
if (flashfsGetSize() > 0) { if (flashfsGetSize() > 0) {

View file

@ -27,15 +27,15 @@
// Automatically trigger a flush when this much data is in the buffer // Automatically trigger a flush when this much data is in the buffer
#define FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN 64 #define FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN 64
void flashfsEraseCompletely(); void flashfsEraseCompletely(void);
void flashfsEraseRange(uint32_t start, uint32_t end); void flashfsEraseRange(uint32_t start, uint32_t end);
uint32_t flashfsGetSize(); uint32_t flashfsGetSize(void);
uint32_t flashfsGetOffset(); uint32_t flashfsGetOffset(void);
uint32_t flashfsGetWriteBufferFreeSpace(); uint32_t flashfsGetWriteBufferFreeSpace(void);
uint32_t flashfsGetWriteBufferSize(); uint32_t flashfsGetWriteBufferSize(void);
int flashfsIdentifyStartOfFreeSpace(); int flashfsIdentifyStartOfFreeSpace(void);
const flashGeometry_t* flashfsGetGeometry(); const flashGeometry_t* flashfsGetGeometry(void);
void flashfsSeekAbs(uint32_t offset); void flashfsSeekAbs(uint32_t offset);
void flashfsSeekRel(int32_t offset); void flashfsSeekRel(int32_t offset);
@ -45,10 +45,10 @@ void flashfsWrite(const uint8_t *data, unsigned int len, bool sync);
int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len); int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len);
bool flashfsFlushAsync(); bool flashfsFlushAsync(void);
void flashfsFlushSync(); void flashfsFlushSync(void);
void flashfsInit(); void flashfsInit(void);
bool flashfsIsReady(); bool flashfsIsReady(void);
bool flashfsIsEOF(); bool flashfsIsEOF(void);

View file

@ -451,7 +451,7 @@ static const struct {
{0, LED_MODE_ORIENTATION}, {0, LED_MODE_ORIENTATION},
}; };
static void applyLedFixedLayers() static void applyLedFixedLayers(void)
{ {
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) { for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex]; const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex];

View file

@ -552,7 +552,7 @@ static uint8_t sa_qhead = 0;
static uint8_t sa_qtail = 0; static uint8_t sa_qtail = 0;
#ifdef DPRINTF_SMARTAUDIO #ifdef DPRINTF_SMARTAUDIO
static int saQueueLength() static int saQueueLength(void)
{ {
if (sa_qhead >= sa_qtail) { if (sa_qhead >= sa_qtail) {
return sa_qhead - sa_qtail; return sa_qhead - sa_qtail;
@ -562,12 +562,12 @@ static int saQueueLength()
} }
#endif #endif
static bool saQueueEmpty() static bool saQueueEmpty(void)
{ {
return sa_qhead == sa_qtail; return sa_qhead == sa_qtail;
} }
static bool saQueueFull() static bool saQueueFull(void)
{ {
return ((sa_qhead + 1) % SA_QSIZE) == sa_qtail; return ((sa_qhead + 1) % SA_QSIZE) == sa_qtail;
} }
@ -670,7 +670,7 @@ void saSetPowerByIndex(uint8_t index)
saQueueCmd(buf, 6); saQueueCmd(buf, 6);
} }
bool vtxSmartAudioInit() bool vtxSmartAudioInit(void)
{ {
#ifdef SMARTAUDIO_DPRINTF #ifdef SMARTAUDIO_DPRINTF
// Setup debugSerialPort // Setup debugSerialPort

View file

@ -1,7 +1,7 @@
// For generic API use, but here for now // For generic API use, but here for now
bool vtxSmartAudioInit(); bool vtxSmartAudioInit(void);
#if 0 #if 0
#ifdef CMS #ifdef CMS

View file

@ -162,7 +162,7 @@ void trampSendRFPower(uint16_t level)
} }
// return false if error // return false if error
bool trampCommitChanges() bool trampCommitChanges(void)
{ {
if(trampStatus != TRAMP_STATUS_ONLINE) if(trampStatus != TRAMP_STATUS_ONLINE)
return false; return false;
@ -238,7 +238,7 @@ typedef enum {
static trampReceiveState_e trampReceiveState = S_WAIT_LEN; static trampReceiveState_e trampReceiveState = S_WAIT_LEN;
static int trampReceivePos = 0; static int trampReceivePos = 0;
static void trampResetReceiver() static void trampResetReceiver(void)
{ {
trampReceiveState = S_WAIT_LEN; trampReceiveState = S_WAIT_LEN;
trampReceivePos = 0; trampReceivePos = 0;
@ -559,7 +559,7 @@ static long trampCmsCommence(displayPort_t *pDisp, const void *self)
return MENU_CHAIN_BACK; return MENU_CHAIN_BACK;
} }
static void trampCmsInitSettings() static void trampCmsInitSettings(void)
{ {
if(trampBand > 0) trampCmsBand = trampBand; if(trampBand > 0) trampCmsBand = trampBand;
if(trampChannel > 0) trampCmsChan = trampChannel; if(trampChannel > 0) trampCmsChan = trampChannel;
@ -577,7 +577,7 @@ static void trampCmsInitSettings()
} }
} }
static long trampCmsOnEnter() static long trampCmsOnEnter(void)
{ {
trampCmsInitSettings(); trampCmsInitSettings();
return 0; return 0;

View file

@ -2,7 +2,7 @@
#if defined(VTX_TRAMP) && defined(VTX_CONTROL) #if defined(VTX_TRAMP) && defined(VTX_CONTROL)
bool vtxTrampInit(); bool vtxTrampInit(void);
#ifdef CMS #ifdef CMS
#include "cms/cms.h" #include "cms/cms.h"

View file

@ -464,7 +464,7 @@ int mspSerialPush(uint8_t cmd, const uint8_t *data, int datalen)
return ret; // return the number of bytes written return ret; // return the number of bytes written
} }
uint32_t mspSerialTxBytesFree() uint32_t mspSerialTxBytesFree(void)
{ {
uint32_t ret = UINT32_MAX; uint32_t ret = UINT32_MAX;

View file

@ -68,7 +68,7 @@ void setupFixedWingAltitudeController(void)
// TODO // TODO
} }
void resetFixedWingAltitudeController() void resetFixedWingAltitudeController(void)
{ {
navPidReset(&posControl.pids.fw_alt); navPidReset(&posControl.pids.fw_alt);
posControl.rcAdjustment[PITCH] = 0; posControl.rcAdjustment[PITCH] = 0;

View file

@ -275,7 +275,7 @@ void jetiExBusDecodeChannelFrame(uint8_t *exBusFrame)
} }
void jetiExBusFrameReset() void jetiExBusFrameReset(void)
{ {
jetiExBusFramePosition = 0; jetiExBusFramePosition = 0;
jetiExBusFrameLength = EXBUS_MAX_CHANNEL_FRAME_SIZE; jetiExBusFrameLength = EXBUS_MAX_CHANNEL_FRAME_SIZE;
@ -370,7 +370,7 @@ static void jetiExBusDataReceive(uint16_t c)
// Check if it is time to read a frame from the data... // Check if it is time to read a frame from the data...
uint8_t jetiExBusFrameStatus() uint8_t jetiExBusFrameStatus(void)
{ {
if (jetiExBusFrameState != EXBUS_STATE_RECEIVED) if (jetiExBusFrameState != EXBUS_STATE_RECEIVED)
return RX_FRAME_PENDING; return RX_FRAME_PENDING;

View file

@ -385,7 +385,7 @@ static void processMspPacket(mspPacket_t* packet)
* - 2: MSP error * - 2: MSP error
* - CRC (request type included) * - CRC (request type included)
*/ */
bool smartPortSendMspReply() bool smartPortSendMspReply(void)
{ {
static uint8_t checksum = 0; static uint8_t checksum = 0;
static uint8_t seq = 0; static uint8_t seq = 0;
@ -743,4 +743,4 @@ void handleSmartPortTelemetry(void)
} }
} }
#endif #endif

View file

@ -88,7 +88,7 @@ RESULT PowerOn(void)
* Output : None. * Output : None.
* Return : USB_SUCCESS. * Return : USB_SUCCESS.
*******************************************************************************/ *******************************************************************************/
RESULT PowerOff() RESULT PowerOff(void)
{ {
/* disable all interrupts and force USB reset */ /* disable all interrupts and force USB reset */
_SetCNTR(CNTR_FRES); _SetCNTR(CNTR_FRES);