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

Fixed compiler warnings.

This commit is contained in:
Martin Budden 2016-05-18 14:49:54 +01:00
parent 4c3c8a1b48
commit 37fe46fdd3
3 changed files with 10 additions and 6 deletions

View file

@ -444,7 +444,7 @@ void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMixers)
#endif
#ifdef USE_SERVOS
void mixerUsePWMIOConfiguration(pwmIOConfiguration_t *pwmIOConfiguration)
void mixerUsePWMIOConfiguration(void)
{
int i;
@ -482,9 +482,8 @@ void mixerUsePWMIOConfiguration(pwmIOConfiguration_t *pwmIOConfiguration)
mixerResetDisarmedMotors();
}
#else
void mixerUsePWMIOConfiguration(pwmIOConfiguration_t *pwmIOConfiguration)
void mixerUsePWMIOConfiguration(void)
{
UNUSED(pwmIOConfiguration);
motorCount = 4;
uint8_t i;
for (i = 0; i < motorCount; i++) {

View file

@ -114,7 +114,7 @@ void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixe
#else
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers);
#endif
void mixerUsePWMIOConfiguration(pwmIOConfiguration_t *pwmIOConfiguration);
void mixerUsePWMIOConfiguration(void);
void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions);
void gpsPreInit(gpsConfig_t *initialGpsConfig);
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
@ -282,9 +282,9 @@ void init(void)
pwmRxInit(masterConfig.inputFilteringMode);
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
pwmIOConfiguration_t *pwmIOConfiguration = pwmInit(&pwm_params);
pwmInit(&pwm_params);
mixerUsePWMIOConfiguration(pwmIOConfiguration);
mixerUsePWMIOConfiguration();
if (!feature(FEATURE_ONESHOT125))
motorControlEnable = true;

View file

@ -23,6 +23,8 @@
#ifdef TELEMETRY
#include "common/utils.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/serial.h"
@ -106,6 +108,9 @@ void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
{
#if defined(TELEMETRY_FRSKY)
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
#else
UNUSED(rxConfig);
UNUSED(deadband3d_throttle);
#endif
#if defined(TELEMETRY_HOTT)