1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

Add void to function declarations/definitions where required

This commit is contained in:
Martin Budden 2017-09-24 08:20:33 +01:00
parent 120955e26b
commit 53f5e87c7a
45 changed files with 130 additions and 128 deletions

View file

@ -55,7 +55,7 @@ static struct {
#endif // USE_SDCARD #endif // USE_SDCARD
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) {
@ -351,7 +351,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;
@ -372,7 +372,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;
@ -511,7 +511,7 @@ bool isBlackboxDeviceFull(void)
} }
} }
unsigned int blackboxGetLogNumber() unsigned int blackboxGetLogNumber(void)
{ {
#ifdef USE_SDCARD #ifdef USE_SDCARD
return blackboxSDCard.largestLogFileNumber; return blackboxSDCard.largestLogFileNumber;
@ -523,7 +523,7 @@ unsigned int blackboxGetLogNumber()
* 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

@ -53,7 +53,7 @@ bool blackboxDeviceBeginLog(void);
bool blackboxDeviceEndLog(bool retainLog); bool blackboxDeviceEndLog(bool retainLog);
bool isBlackboxDeviceFull(void); bool isBlackboxDeviceFull(void);
unsigned int blackboxGetLogNumber(); unsigned int blackboxGetLogNumber(void);
void blackboxReplenishHeaderBudget(); void blackboxReplenishHeaderBudget(void);
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes); blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes);

View file

@ -69,7 +69,7 @@ static char cmsx_BlackboxStatus[CMS_BLACKBOX_STRING_LENGTH];
static char cmsx_BlackboxDeviceStorageUsed[CMS_BLACKBOX_STRING_LENGTH]; static char cmsx_BlackboxDeviceStorageUsed[CMS_BLACKBOX_STRING_LENGTH];
static char cmsx_BlackboxDeviceStorageFree[CMS_BLACKBOX_STRING_LENGTH]; static char cmsx_BlackboxDeviceStorageFree[CMS_BLACKBOX_STRING_LENGTH];
static void cmsx_Blackbox_GetDeviceStatus() static void cmsx_Blackbox_GetDeviceStatus(void)
{ {
char * unit = "B"; char * unit = "B";
#if defined(USE_SDCARD) || defined(USE_FLASHFS) #if defined(USE_SDCARD) || defined(USE_FLASHFS)

View file

@ -156,7 +156,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;
@ -174,7 +174,7 @@ static void trampCmsInitSettings()
} }
} }
static long trampCmsOnEnter() static long trampCmsOnEnter(void)
{ {
trampCmsInitSettings(); trampCmsInitSettings();
return 0; return 0;

View file

@ -43,7 +43,7 @@ void intFeatureClearAll(uint32_t *features)
*features = 0; *features = 0;
} }
void latchActiveFeatures() void latchActiveFeatures(void)
{ {
activeFeaturesLatch = featureConfig()->enabledFeatures; activeFeaturesLatch = featureConfig()->enabledFeatures;
} }
@ -68,7 +68,7 @@ void featureClear(uint32_t mask)
intFeatureClear(mask, &featureConfigMutable()->enabledFeatures); intFeatureClear(mask, &featureConfigMutable()->enabledFeatures);
} }
void featureClearAll() void featureClearAll(void)
{ {
intFeatureClearAll(&featureConfigMutable()->enabledFeatures); intFeatureClearAll(&featureConfigMutable()->enabledFeatures);
} }

View file

@ -85,7 +85,7 @@ int pgStore(const pgRegistry_t* reg, void *to, int size)
return take; return take;
} }
void pgResetAll() void pgResetAll(void)
{ {
PG_FOREACH(reg) { PG_FOREACH(reg) {
pgReset(reg); pgReset(reg);

View file

@ -186,7 +186,7 @@ const pgRegistry_t* pgFind(pgn_t pgn);
void pgLoad(const pgRegistry_t* reg, const void *from, int size, int version); void pgLoad(const pgRegistry_t* reg, const void *from, int size, int version);
int pgStore(const pgRegistry_t* reg, void *to, int size); int pgStore(const pgRegistry_t* reg, void *to, int size);
void pgResetAll(); void pgResetAll(void);
void pgResetInstance(const pgRegistry_t *reg, uint8_t *base); void pgResetInstance(const pgRegistry_t *reg, uint8_t *base);
bool pgResetCopy(void *copy, pgn_t pgn); bool pgResetCopy(void *copy, pgn_t pgn);
void pgReset(const pgRegistry_t* reg); void pgReset(const pgRegistry_t* reg);

View file

@ -77,14 +77,14 @@ static struct {
static uint32_t endTimeMillis; static uint32_t endTimeMillis;
#ifdef CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE #ifdef CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE
void TIM6_DAC_IRQHandler() void TIM6_DAC_IRQHandler(void)
{ {
IOHi(cameraControlRuntime.io); IOHi(cameraControlRuntime.io);
TIM6->SR = 0; TIM6->SR = 0;
} }
void TIM7_IRQHandler() void TIM7_IRQHandler(void)
{ {
IOLo(cameraControlRuntime.io); IOLo(cameraControlRuntime.io);
@ -92,7 +92,7 @@ void TIM7_IRQHandler()
} }
#endif #endif
void cameraControlInit() void cameraControlInit(void)
{ {
if (cameraControlConfig()->ioTag == IO_TAG_NONE) if (cameraControlConfig()->ioTag == IO_TAG_NONE)
return; return;

View file

@ -49,7 +49,7 @@ typedef struct cameraControlConfig_s {
PG_DECLARE(cameraControlConfig_t, cameraControlConfig); PG_DECLARE(cameraControlConfig_t, cameraControlConfig);
void cameraControlInit(); void cameraControlInit(void);
void cameraControlProcess(uint32_t currentTimeUs); void cameraControlProcess(uint32_t currentTimeUs);
void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs); void cameraControlKeyPress(cameraControlKey_e key, uint32_t holdDurationMs);

View file

@ -73,7 +73,7 @@ void cc2500SetPower(uint8_t power)
cc2500WriteReg(CC2500_3E_PATABLE, patable[power]); cc2500WriteReg(CC2500_3E_PATABLE, patable[power]);
} }
uint8_t cc2500Reset() uint8_t cc2500Reset(void)
{ {
cc2500Strobe(CC2500_SRES); cc2500Strobe(CC2500_SRES);
delayMicroseconds(1000); // 1000us delayMicroseconds(1000); // 1000us

View file

@ -150,4 +150,4 @@ uint8_t cc2500ReadReg(uint8_t reg);
void cc2500Strobe(uint8_t address); void cc2500Strobe(uint8_t address);
uint8_t cc2500WriteReg(uint8_t address, uint8_t data); uint8_t cc2500WriteReg(uint8_t address, uint8_t data);
void cc2500SetPower(uint8_t power); void cc2500SetPower(uint8_t power);
uint8_t cc2500Reset(); uint8_t cc2500Reset(void);

View file

@ -152,7 +152,7 @@ static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
} }
#endif #endif
static bool ak8963Init() static bool ak8963Init(void)
{ {
uint8_t calibration[3]; uint8_t calibration[3];
uint8_t status; uint8_t status;

View file

@ -59,7 +59,7 @@
#define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value #define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
#define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value #define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
static bool ak8975Init() static bool ak8975Init(void)
{ {
uint8_t buffer[3]; uint8_t buffer[3];
uint8_t status; uint8_t status;

View file

@ -632,7 +632,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;
} }
@ -647,7 +647,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

@ -66,11 +66,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

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

View file

@ -110,7 +110,7 @@ void setPreferredBeeperOffMask(uint32_t mask);
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

@ -131,7 +131,7 @@ void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsD
saveConfigAndNotify(); saveConfigAndNotify();
} }
static bool isCalibrating() static bool isCalibrating(void)
{ {
#ifdef BARO #ifdef BARO
if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) { if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) {

View file

@ -36,7 +36,7 @@ PG_DECLARE(throttleCorrectionConfig_t, throttleCorrectionConfig);
union rollAndPitchTrims_u; union rollAndPitchTrims_u;
void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta); void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta);
void handleInflightCalibrationStickPosition(); void handleInflightCalibrationStickPosition(void);
void resetArmingDisabled(void); void resetArmingDisabled(void);

View file

@ -80,7 +80,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

@ -539,7 +539,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;
} }
@ -548,7 +548,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;
} }
@ -806,7 +806,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
@ -836,7 +836,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;
} }
@ -1618,7 +1618,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();
} }
@ -2364,7 +2364,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) {
@ -3211,7 +3211,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);
@ -3229,7 +3229,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;
} }
@ -3238,7 +3238,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();
@ -3256,7 +3256,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();
@ -3361,7 +3361,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;
@ -3491,7 +3491,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()) {
@ -3554,17 +3554,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;
@ -3646,7 +3646,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

@ -181,7 +181,7 @@ static void drawHorizonalPercentageBar(uint8_t width,uint8_t percent)
} }
#if 0 #if 0
static void fillScreenWithCharacters() static void fillScreenWithCharacters(void)
{ {
for (uint8_t row = 0; row < SCREEN_CHARACTER_ROW_COUNT; row++) { for (uint8_t row = 0; row < SCREEN_CHARACTER_ROW_COUNT; row++) {
for (uint8_t column = 0; column < SCREEN_CHARACTER_COLUMN_COUNT; column++) { for (uint8_t column = 0; column < SCREEN_CHARACTER_COLUMN_COUNT; column++) {
@ -241,7 +241,7 @@ static void updateFailsafeStatus(void)
i2c_OLED_send_char(bus, failsafeIndicator); i2c_OLED_send_char(bus, failsafeIndicator);
} }
static void showTitle() static void showTitle(void)
{ {
i2c_OLED_set_line(bus, 0); i2c_OLED_set_line(bus, 0);
i2c_OLED_send_string(bus, pageState.page->title); i2c_OLED_send_string(bus, pageState.page->title);
@ -346,7 +346,7 @@ static void showProfilePage(void)
#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2) #define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2)
#ifdef GPS #ifdef GPS
static void showGpsPage() static void showGpsPage(void)
{ {
if (!feature(FEATURE_GPS)) { if (!feature(FEATURE_GPS)) {
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE; pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;

View file

@ -52,12 +52,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;
} }
@ -67,7 +67,7 @@ static void flashfsSetTailAddress(uint32_t address)
tailAddress = address; tailAddress = address;
} }
void flashfsEraseCompletely() void flashfsEraseCompletely(void)
{ {
m25p16_eraseCompletely(); m25p16_eraseCompletely();
@ -106,17 +106,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;
@ -127,7 +127,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;
} }
@ -135,12 +135,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();
} }
@ -270,7 +270,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];
@ -305,7 +305,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
@ -328,7 +328,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
@ -484,7 +484,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
@ -553,14 +553,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

@ -23,16 +23,16 @@
// 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);
struct flashGeometry_s; struct flashGeometry_s;
const struct flashGeometry_s* flashfsGetGeometry(); const struct flashGeometry_s* flashfsGetGeometry(void);
void flashfsSeekAbs(uint32_t offset); void flashfsSeekAbs(uint32_t offset);
void flashfsSeekRel(int32_t offset); void flashfsSeekRel(int32_t offset);
@ -42,10 +42,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

@ -441,7 +441,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];
@ -1146,7 +1146,7 @@ bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex)
return true; return true;
} }
void ledStripInit() void ledStripInit(void)
{ {
colors = ledStripConfigMutable()->colors; colors = ledStripConfigMutable()->colors;
modeColors = ledStripConfig()->modeColors; modeColors = ledStripConfig()->modeColors;

View file

@ -163,7 +163,7 @@ static escSensorData_t *escData;
/** /**
* Gets the correct altitude symbol for the current unit system * Gets the correct altitude symbol for the current unit system
*/ */
static char osdGetMetersToSelectedUnitSymbol() static char osdGetMetersToSelectedUnitSymbol(void)
{ {
switch (osdConfig()->units) { switch (osdConfig()->units) {
case OSD_UNIT_IMPERIAL: case OSD_UNIT_IMPERIAL:

View file

@ -83,7 +83,7 @@ static void sendCtrlCommand(rcsplit_ctrl_argument_e argument)
serialWriteBuf(rcSplitSerialPort, uart_buffer, 5); serialWriteBuf(rcSplitSerialPort, uart_buffer, 5);
} }
static void rcSplitProcessMode() static void rcSplitProcessMode(void)
{ {
// if the device not ready, do not handle any mode change event // if the device not ready, do not handle any mode change event
if (RCSPLIT_STATE_IS_READY != cameraState) if (RCSPLIT_STATE_IS_READY != cameraState)

View file

@ -41,4 +41,4 @@ PG_DECLARE(vtxRTC6705Config_t, vtxRTC6705Config);
extern const char * const rtc6705PowerNames[RTC6705_POWER_COUNT]; extern const char * const rtc6705PowerNames[RTC6705_POWER_COUNT];
void vtxRTC6705Configure(void); void vtxRTC6705Configure(void);
bool vtxRTC6705Init(); bool vtxRTC6705Init(void);

View file

@ -491,7 +491,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;
@ -501,12 +501,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;
} }
@ -609,7 +609,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

@ -60,7 +60,7 @@ void saSetBandAndChannel(uint8_t band, uint8_t channel);
void saSetMode(int mode); void saSetMode(int mode);
void saSetPowerByIndex(uint8_t index); void saSetPowerByIndex(uint8_t index);
void saSetFreq(uint16_t freq); void saSetFreq(uint16_t freq);
bool vtxSmartAudioInit(); bool vtxSmartAudioInit(void);
#ifdef SMARTAUDIO_DPRINTF #ifdef SMARTAUDIO_DPRINTF
#ifdef OMNIBUSF4 #ifdef OMNIBUSF4

View file

@ -157,7 +157,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;
@ -233,7 +233,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;

View file

@ -12,8 +12,8 @@ extern uint32_t trampCurFreq;
extern uint16_t trampConfiguredPower; // Configured transmitting power extern uint16_t trampConfiguredPower; // Configured transmitting power
extern int16_t trampTemperature; extern int16_t trampTemperature;
bool vtxTrampInit(); bool vtxTrampInit(void);
bool trampCommitChanges(); bool trampCommitChanges(void);
void trampSetPitMode(uint8_t onoff); void trampSetPitMode(uint8_t onoff);
void trampSetBandAndChannel(uint8_t band, uint8_t channel); void trampSetBandAndChannel(uint8_t band, uint8_t channel);
void trampSetRFPower(uint16_t level); void trampSetRFPower(uint16_t level);

View file

@ -301,7 +301,7 @@ int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direct
} }
uint32_t mspSerialTxBytesFree() uint32_t mspSerialTxBytesFree(void)
{ {
uint32_t ret = UINT32_MAX; uint32_t ret = UINT32_MAX;

View file

@ -193,25 +193,25 @@ static void telemetry_build_frame(uint8_t *packet)
#endif #endif
#if defined(USE_FRSKY_RX_PA_LNA) #if defined(USE_FRSKY_RX_PA_LNA)
static void RX_enable() static void RX_enable(void)
{ {
IOLo(txEnPin); IOLo(txEnPin);
IOHi(rxEnPin); IOHi(rxEnPin);
} }
static void TX_enable() static void TX_enable(void)
{ {
IOLo(rxEnPin); IOLo(rxEnPin);
IOHi(txEnPin); IOHi(txEnPin);
} }
#endif #endif
void frSkyDBind() void frSkyDBind(void)
{ {
bindRequested = true; bindRequested = true;
} }
static void initialize() static void initialize(void)
{ {
cc2500Reset(); cc2500Reset();
cc2500WriteReg(CC2500_02_IOCFG0, 0x01); cc2500WriteReg(CC2500_02_IOCFG0, 0x01);

View file

@ -36,4 +36,4 @@ struct rxRuntimeConfig_s;
void frSkyDInit(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig); void frSkyDInit(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
void frSkyDSetRcData(uint16_t *rcData, const uint8_t *payload); void frSkyDSetRcData(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e frSkyDDataReceived(uint8_t *payload); rx_spi_received_e frSkyDDataReceived(uint8_t *payload);
void frSkyDBind(); void frSkyDBind(void);

View file

@ -281,7 +281,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;
@ -376,7 +376,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...
static uint8_t jetiExBusFrameStatus() static uint8_t jetiExBusFrameStatus(void)
{ {
if (jetiExBusFrameState != EXBUS_STATE_RECEIVED) if (jetiExBusFrameState != EXBUS_STATE_RECEIVED)
return RX_FRAME_PENDING; return RX_FRAME_PENDING;

View file

@ -86,14 +86,14 @@ static biquadFilter_t fftFreqFilter[3];
// Hanning window, see https://en.wikipedia.org/wiki/Window_function#Hann_.28Hanning.29_window // Hanning window, see https://en.wikipedia.org/wiki/Window_function#Hann_.28Hanning.29_window
static float hanningWindow[FFT_WINDOW_SIZE]; static float hanningWindow[FFT_WINDOW_SIZE];
void initHanning() void initHanning(void)
{ {
for (int i = 0; i < FFT_WINDOW_SIZE; i++) { for (int i = 0; i < FFT_WINDOW_SIZE; i++) {
hanningWindow[i] = (0.5 - 0.5 * cosf(2 * M_PIf * i / (FFT_WINDOW_SIZE - 1))); hanningWindow[i] = (0.5 - 0.5 * cosf(2 * M_PIf * i / (FFT_WINDOW_SIZE - 1)));
} }
} }
void initGyroData() void initGyroData(void)
{ {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
for (int i = 0; i < FFT_WINDOW_SIZE; i++) { for (int i = 0; i < FFT_WINDOW_SIZE; i++) {

View file

@ -31,4 +31,4 @@ const gyroFftData_t *gyroFftData(int axis);
struct gyroDev_s; struct gyroDev_s;
void gyroDataAnalyse(const struct gyroDev_s *gyroDev, biquadFilter_t *notchFilterDyn); void gyroDataAnalyse(const struct gyroDev_s *gyroDev, biquadFilter_t *notchFilterDyn);
void gyroDataAnalyseUpdate(biquadFilter_t *notchFilterDyn); void gyroDataAnalyseUpdate(biquadFilter_t *notchFilterDyn);
bool isDynamicFilterActive(); bool isDynamicFilterActive(void);

View file

@ -71,7 +71,7 @@ uint8_t interruptCounter = 0;
#define DELAY_SENDING_BYTE 40 #define DELAY_SENDING_BYTE 40
void bstProcessInCommand(void); void bstProcessInCommand(void);
void I2C_EV_IRQHandler() void I2C_EV_IRQHandler(void)
{ {
if (I2C_GetITStatus(BSTx, I2C_IT_ADDR)) { if (I2C_GetITStatus(BSTx, I2C_IT_ADDR)) {
CRC8 = 0; CRC8 = 0;
@ -154,17 +154,17 @@ void I2C_EV_IRQHandler()
} }
} }
void I2C1_EV_IRQHandler() void I2C1_EV_IRQHandler(void)
{ {
I2C_EV_IRQHandler(); I2C_EV_IRQHandler();
} }
void I2C2_EV_IRQHandler() void I2C2_EV_IRQHandler(void)
{ {
I2C_EV_IRQHandler(); I2C_EV_IRQHandler();
} }
uint32_t bstTimeoutUserCallback() uint32_t bstTimeoutUserCallback(void)
{ {
bstErrorCount++; bstErrorCount++;

View file

@ -250,11 +250,11 @@ void FLASH_Lock(void);
FLASH_Status FLASH_ErasePage(uintptr_t Page_Address); FLASH_Status FLASH_ErasePage(uintptr_t Page_Address);
FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t Data); FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t Data);
uint64_t nanos64_real(); uint64_t nanos64_real(void);
uint64_t micros64_real(); uint64_t micros64_real(void);
uint64_t millis64_real(); uint64_t millis64_real(void);
void delayMicroseconds_real(uint32_t us); void delayMicroseconds_real(uint32_t us);
uint64_t micros64(); uint64_t micros64(void);
uint64_t millis64(); uint64_t millis64(void);
int lockMainPID(void); int lockMainPID(void);

View file

@ -527,7 +527,7 @@ static inline bool shouldPrepareHoTTMessages(uint32_t currentMicros)
return currentMicros - lastMessagesPreparedAt >= HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ; return currentMicros - lastMessagesPreparedAt >= HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ;
} }
static inline bool shouldCheckForHoTTRequest() static inline bool shouldCheckForHoTTRequest(void)
{ {
if (hottIsSending) { if (hottIsSending) {
return false; return false;

View file

@ -202,7 +202,7 @@ static void ltm_sframe(void)
* Attitude A-frame - 10 Hz at > 2400 baud * Attitude A-frame - 10 Hz at > 2400 baud
* PITCH ROLL HEADING * PITCH ROLL HEADING
*/ */
static void ltm_aframe() static void ltm_aframe(void)
{ {
ltm_initialise_packet('A'); ltm_initialise_packet('A');
ltm_serialise_16(DECIDEGREES_TO_DEGREES(attitude.values.pitch)); ltm_serialise_16(DECIDEGREES_TO_DEGREES(attitude.values.pitch));
@ -216,7 +216,7 @@ static void ltm_aframe()
* This frame will be ignored by Ghettostation, but processed by GhettOSD if it is used as standalone onboard OSD * This frame will be ignored by Ghettostation, but processed by GhettOSD if it is used as standalone onboard OSD
* home pos, home alt, direction to home * home pos, home alt, direction to home
*/ */
static void ltm_oframe() static void ltm_oframe(void)
{ {
ltm_initialise_packet('O'); ltm_initialise_packet('O');
#if defined(GPS) #if defined(GPS)

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);