From 8e79e8092ea8019fc7f0e9d6810c758f996c0505 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sun, 22 Jan 2017 22:39:37 +0000 Subject: [PATCH] Fixed up whitespace --- src/main/drivers/accgyro_spi_mpu6500.c | 2 +- src/main/drivers/bus_i2c_hal.c | 4 ++-- src/main/drivers/flash.h | 2 +- src/main/drivers/light_led.h | 4 ++-- src/main/drivers/vtx_rtc6705.c | 2 +- src/main/fc/cli.c | 6 +++--- src/main/fc/config.c | 4 ++-- src/main/flight/mixer.c | 2 +- src/main/io/gps.h | 2 +- src/main/io/vtx_smartaudio.c | 2 +- src/main/io/vtx_tramp.c | 10 +++++----- src/main/rx/crsf.c | 2 +- src/main/rx/spektrum.c | 12 +++++------ src/main/rx/spektrum.h | 10 +++++----- src/main/sensors/acceleration.c | 4 ++-- src/main/sensors/acceleration.h | 2 +- src/main/sensors/gyro.c | 2 +- .../target/ALIENFLIGHTF3/initialisation.c | 2 +- src/main/target/ALIENFLIGHTF3/target.c | 2 +- src/main/target/BLUEJAYF4/config.c | 2 +- src/main/target/BLUEJAYF4/hardware_revision.c | 4 ++-- src/main/target/BLUEJAYF4/initialisation.c | 8 ++++---- src/main/target/BLUEJAYF4/target.h | 12 +++++------ src/main/target/CJMCU/initialisation.c | 2 +- src/main/target/COLIBRI_RACE/config.c | 4 ++-- src/main/target/COLIBRI_RACE/i2c_bst.c | 2 +- src/main/target/ELLE0/target.h | 6 +++--- src/main/target/FISHDRONEF4/target.c | 12 +++++------ src/main/target/FISHDRONEF4/target.h | 4 ++-- src/main/target/KIWIF4/target.c | 10 +++++----- src/main/target/KIWIF4/target.h | 4 ++-- src/main/target/NAZE/initialisation.c | 2 +- src/main/target/NERO/target.h | 2 +- src/main/target/RG_SSD_F3/target.c | 20 +++++++++---------- src/main/target/RG_SSD_F3/target.h | 2 +- src/main/target/SPRACINGF3MINI/target.c | 2 +- src/main/target/TINYFISH/config.c | 2 +- src/main/target/TINYFISH/target.h | 14 ++++++------- src/main/telemetry/ibus.c | 6 +++--- src/main/telemetry/smartport.c | 6 +++--- 40 files changed, 101 insertions(+), 101 deletions(-) diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index f76733d4d..8a5eab99b 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -141,7 +141,7 @@ bool mpu6500SpiGyroDetect(gyroDev_t *gyro) if (gyro->mpuDetectionResult.sensor != mpuDetected || !mpuDetected) { return false; } - + gyro->init = mpu6500SpiGyroInit; gyro->read = mpuGyroRead; gyro->intStatus = mpuCheckDataReady; diff --git a/src/main/drivers/bus_i2c_hal.c b/src/main/drivers/bus_i2c_hal.c index 75c83c870..528774e29 100644 --- a/src/main/drivers/bus_i2c_hal.c +++ b/src/main/drivers/bus_i2c_hal.c @@ -62,7 +62,7 @@ static void i2cUnstick(IO_t scl, IO_t sda); #define I2C3_SDA PB4 #endif -#if defined(USE_I2C4) +#if defined(USE_I2C4) #ifndef I2C4_SCL #define I2C4_SCL PD12 #endif @@ -198,7 +198,7 @@ void i2cInit(I2CDevice device) case I2CDEV_3: __HAL_RCC_I2C3_CLK_ENABLE(); break; -#ifdef USE_I2C4 +#ifdef USE_I2C4 case I2CDEV_4: __HAL_RCC_I2C4_CLK_ENABLE(); break; diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h index 6a6f160b0..f9158b15e 100644 --- a/src/main/drivers/flash.h +++ b/src/main/drivers/flash.h @@ -32,5 +32,5 @@ typedef struct flashGeometry_s { } flashGeometry_t; typedef struct flashConfig_s { - ioTag_t csTag; + ioTag_t csTag; } flashConfig_t; diff --git a/src/main/drivers/light_led.h b/src/main/drivers/light_led.h index d1ae47294..25961579e 100644 --- a/src/main/drivers/light_led.h +++ b/src/main/drivers/light_led.h @@ -22,8 +22,8 @@ #define LED_NUMBER 3 typedef struct statusLedConfig_s { - ioTag_t ledTags[LED_NUMBER]; - uint8_t polarity; + ioTag_t ledTags[LED_NUMBER]; + uint8_t polarity; } statusLedConfig_t; // Helpful macros diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index ea9403b87..36e6be4d5 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -145,7 +145,7 @@ bool rtc6705Init(void) vtxPowerPin = IOGetByTag(IO_TAG(RTC6705_POWER_PIN)); IOInit(vtxPowerPin, OWNER_VTX, 0); IOConfigGPIO(vtxPowerPin, IOCFG_OUT_PP); - + ENABLE_VTX_POWER; #endif diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 84363ca17..e030e4e2d 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -435,7 +435,7 @@ static const lookupTableEntry_t lookupTables[] = { { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }, { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) }, { lookupTableRcInterpolation, sizeof(lookupTableRcInterpolation) / sizeof(char *) }, - { lookupTableRcInterpolationChannels, sizeof(lookupTableRcInterpolationChannels) / sizeof(char *) }, + { lookupTableRcInterpolationChannels, sizeof(lookupTableRcInterpolationChannels) / sizeof(char *) }, { lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) }, { lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) }, #ifdef OSD @@ -3582,7 +3582,7 @@ static void printConfig(char *cmdline, bool doDiff) #ifdef USE_RESOURCE_MGMT cliPrintHashLine("resources"); printResource(dumpMask, &defaultConfig); -#endif +#endif #ifndef USE_QUAD_MIXER_ONLY cliPrintHashLine("mixer"); @@ -3772,7 +3772,7 @@ const clicmd_t cmdTable[] = { #ifdef LED_STRIP CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor), #endif - CLI_COMMAND_DEF("motor", "get/set motor", " []", cliMotor), + CLI_COMMAND_DEF("motor", "get/set motor", " []", cliMotor), CLI_COMMAND_DEF("name", "name of craft", NULL, cliName), #if (FLASH_SIZE > 128) CLI_COMMAND_DEF("play_sound", NULL, "[]", cliPlaySound), diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 523fc9640..7d5b67185 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -527,7 +527,7 @@ void resetStatusLedConfig(statusLedConfig_t *statusLedConfig) #ifdef LED2_INVERTED | BIT(2) #endif - ; + ; } #ifdef USE_FLASHFS @@ -857,7 +857,7 @@ void createDefaultConfig(master_t *config) /* merely to force a reset if the person inadvertently flashes the wrong target */ strncpy(config->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER)); - + #if defined(TARGET_CONFIG) targetConfiguration(config); #endif diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index a5a7244ff..8ee4bb574 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -254,7 +254,7 @@ bool isMotorProtocolDshot(void) { case PWM_TYPE_DSHOT150: return true; default: - return false; + return false; } #else return false; diff --git a/src/main/io/gps.h b/src/main/io/gps.h index 37ca6968d..484f7bf52 100644 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -78,7 +78,7 @@ typedef enum { GPS_MESSAGE_STATE_IDLE = 0, GPS_MESSAGE_STATE_INIT, GPS_MESSAGE_STATE_SBAS, - GPS_MESSAGE_STATE_ENTRY_COUNT + GPS_MESSAGE_STATE_ENTRY_COUNT } gpsMessageState_e; typedef struct gpsData_s { diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 29811bbfc..e87db2694 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -118,7 +118,7 @@ enum { // opmode flags, SET side #define SA_MODE_SET_IN_RANGE_PITMODE 1 // Immediate -#define SA_MODE_SET_OUT_RANGE_PITMODE 2 // Immediate +#define SA_MODE_SET_OUT_RANGE_PITMODE 2 // Immediate #define SA_MODE_CLR_PITMODE 4 // Immediate #define SA_MODE_SET_UNLOCK 8 #define SA_MODE_SET_LOCK 0 // ~UNLOCK diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 45e75d7cf..749a0d40c 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -325,7 +325,7 @@ bool trampInit() vtxTramp.vTable = &trampVTable; vtxCommonRegisterDevice(&vtxTramp); #endif - + return true; } @@ -346,7 +346,7 @@ void vtxTrampProcess(uint32_t currentTimeUs) #ifdef TRAMP_DEBUG debug[0] = trampStatus; #endif - + switch(replyCode) { case 'r': if (trampStatus <= TRAMP_STATUS_OFFLINE) @@ -374,7 +374,7 @@ void vtxTrampProcess(uint32_t currentTimeUs) else trampQueryS(); } - + lastQueryTimeUs = currentTimeUs; } break; @@ -426,7 +426,7 @@ void vtxTrampProcess(uint32_t currentTimeUs) debug[2] = debugPowReqCounter; debug[3] = 0; #endif - + #ifdef CMS trampCmsUpdateStatusString(); #endif @@ -552,7 +552,7 @@ static void trampCmsInitSettings() { if(trampCurBand > 0) trampCmsBand = trampCurBand; if(trampCurChan > 0) trampCmsChan = trampCurChan; - + trampCmsUpdateFreqRef(); trampCmsPitmode = trampCurPitmode + 1; diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 8d6b5dd34..25d5151b1 100644 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -209,7 +209,7 @@ void crsfRxSendTelemetryData(void) // and that there is time to send the telemetry frame before the next RX frame arrives if (CRSF_PORT_OPTIONS & SERIAL_BIDIR) { const uint32_t timeSinceStartOfFrame = micros() - crsfFrameStartAt; - if ((timeSinceStartOfFrame < CRSF_TIME_NEEDED_PER_FRAME_US) || + if ((timeSinceStartOfFrame < CRSF_TIME_NEEDED_PER_FRAME_US) || (timeSinceStartOfFrame > CRSF_TIME_BETWEEN_FRAMES_US - CRSF_TIME_NEEDED_PER_FRAME_US)) { return; } diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 640f7d89e..66844ee03 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -276,7 +276,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig case SERIALRX_SRXL: #ifdef TELEMETRY srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared && rxConfig->serialrx_provider == SERIALRX_SRXL); -#endif +#endif case SERIALRX_SPEKTRUM2048: // 11 bit frames spek_chan_shift = 3; @@ -298,11 +298,11 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig rxRuntimeConfig->rcReadRawFn = spektrumReadRawRC; rxRuntimeConfig->rcFrameStatusFn = spektrumFrameStatus; - serialPort = openSerialPort(portConfig->identifier, - FUNCTION_RX_SERIAL, - spektrumDataReceive, - SPEKTRUM_BAUDRATE, - portShared || srxlEnabled ? MODE_RXTX : MODE_RX, + serialPort = openSerialPort(portConfig->identifier, + FUNCTION_RX_SERIAL, + spektrumDataReceive, + SPEKTRUM_BAUDRATE, + portShared || srxlEnabled ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED | (srxlEnabled ? SERIAL_BIDIR : 0)); #ifdef TELEMETRY diff --git a/src/main/rx/spektrum.h b/src/main/rx/spektrum.h index 58ed4a3cd..4fcfed7c5 100644 --- a/src/main/rx/spektrum.h +++ b/src/main/rx/spektrum.h @@ -17,12 +17,12 @@ #pragma once -#define SPEKTRUM_SAT_BIND_DISABLED 0 -#define SPEKTRUM_SAT_BIND_MAX 10 +#define SPEKTRUM_SAT_BIND_DISABLED 0 +#define SPEKTRUM_SAT_BIND_MAX 10 -#define SPEK_FRAME_SIZE 16 -#define SRXL_FRAME_OVERHEAD 5 -#define SRXL_FRAME_SIZE_MAX (SPEK_FRAME_SIZE + SRXL_FRAME_OVERHEAD) +#define SPEK_FRAME_SIZE 16 +#define SRXL_FRAME_OVERHEAD 5 +#define SRXL_FRAME_SIZE_MAX (SPEK_FRAME_SIZE + SRXL_FRAME_OVERHEAD) void spektrumBind(rxConfig_t *rxConfig); bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 325de5988..ded23de3c 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -192,9 +192,9 @@ retry: case ICM_20602_SPI: accHardware = ACC_ICM20602; break; - default: + default: accHardware = ACC_MPU6500; - } + } break; } #endif diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index b91db0ee1..fda259e94 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -34,7 +34,7 @@ typedef enum { ACC_ICM20689, ACC_MPU9250, ACC_ICM20608G, - ACC_ICM20602, + ACC_ICM20602, ACC_FAKE } accelerationSensor_e; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index ad6afffbe..9732a9685 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -175,7 +175,7 @@ static bool gyroDetect(gyroDev_t *dev) case ICM_20602_SPI: gyroHardware = GYRO_ICM20602; break; - default: + default: gyroHardware = GYRO_MPU6500; } #ifdef GYRO_MPU6500_ALIGN diff --git a/src/main/target/ALIENFLIGHTF3/initialisation.c b/src/main/target/ALIENFLIGHTF3/initialisation.c index 53fbb1f91..f435cb994 100644 --- a/src/main/target/ALIENFLIGHTF3/initialisation.c +++ b/src/main/target/ALIENFLIGHTF3/initialisation.c @@ -25,7 +25,7 @@ void targetBusInit(void) { - #ifdef USE_SPI + #ifdef USE_SPI #ifdef USE_SPI_DEVICE_1 spiInit(SPIDEV_1); #endif diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 267b2c658..ab89b1048 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -28,7 +28,7 @@ // Motor 7 is only working if battery monitoring is disabled const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // up to 10 Motor Outputs + // up to 10 Motor Outputs /* DEF_TIM(TIM15, CH2, PB15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM1 - PB15 - DMA_NONE - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM2 - PB14 - DMA1_CH5 - TIM1_CH2N, *TIM15_CH1 diff --git a/src/main/target/BLUEJAYF4/config.c b/src/main/target/BLUEJAYF4/config.c index 3ea9d9f7d..d774c765e 100644 --- a/src/main/target/BLUEJAYF4/config.c +++ b/src/main/target/BLUEJAYF4/config.c @@ -52,7 +52,7 @@ void targetValidateConfiguration(master_t *config) /* make sure the SDCARD cannot be turned on */ if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) { intFeatureClear(FEATURE_SDCARD, &config->enabledFeatures); - + if (config->blackboxConfig.device == BLACKBOX_DEVICE_SDCARD) { config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH; } diff --git a/src/main/target/BLUEJAYF4/hardware_revision.c b/src/main/target/BLUEJAYF4/hardware_revision.c index 95db1c618..5f87926f9 100644 --- a/src/main/target/BLUEJAYF4/hardware_revision.c +++ b/src/main/target/BLUEJAYF4/hardware_revision.c @@ -50,10 +50,10 @@ void detectHardwareRevision(void) IO_t pin2 = IOGetByTag(IO_TAG(PB13)); IOInit(pin2, OWNER_SYSTEM, 2); IOConfigGPIO(pin2, IOCFG_IPU); - + if (!IORead(pin2)) { hardwareRevision = BJF4_REV4; - } + } } else { IO_t pin2 = IOGetByTag(IO_TAG(PB13)); IOInit(pin2, OWNER_SYSTEM, 2); diff --git a/src/main/target/BLUEJAYF4/initialisation.c b/src/main/target/BLUEJAYF4/initialisation.c index 389f12e64..312c4511f 100644 --- a/src/main/target/BLUEJAYF4/initialisation.c +++ b/src/main/target/BLUEJAYF4/initialisation.c @@ -36,11 +36,11 @@ void targetPreInit(void) default: return; } - + IO_t inverter = IOGetByTag(IO_TAG(UART1_INVERTER)); IOInit(inverter, OWNER_INVERTER, 1); IOConfigGPIO(inverter, IOCFG_OUT_PP); - + bool high = false; serialPortConfig_t *portConfig = serialFindPortConfiguration(SERIAL_PORT_USART1); if (portConfig) { @@ -54,12 +54,12 @@ void targetPreInit(void) high = !high; } IOWrite(inverter, high); - + /* ensure the CS pin for the flash is pulled hi so any SD card initialisation does not impact the chip */ if (hardwareRevision == BJF4_REV3) { IO_t io = IOGetByTag(IO_TAG(M25P16_CS_PIN)); IOConfigGPIO(io, IOCFG_OUT_PP); IOHi(io); - } + } } diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 34d4a9804..db082c2e4 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -163,10 +163,10 @@ #define SPEKTRUM_BIND #define BIND_PIN PB11 -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) -#define USABLE_TIMER_CHANNEL_COUNT 7 -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) +#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/CJMCU/initialisation.c b/src/main/target/CJMCU/initialisation.c index 817dfc540..884ea0335 100644 --- a/src/main/target/CJMCU/initialisation.c +++ b/src/main/target/CJMCU/initialisation.c @@ -32,5 +32,5 @@ void targetBusInit(void) if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) { serialRemovePort(SERIAL_PORT_USART3); i2cInit(I2C_DEVICE); - } + } } \ No newline at end of file diff --git a/src/main/target/COLIBRI_RACE/config.c b/src/main/target/COLIBRI_RACE/config.c index ed8e8ab55..535da3d20 100644 --- a/src/main/target/COLIBRI_RACE/config.c +++ b/src/main/target/COLIBRI_RACE/config.c @@ -29,7 +29,7 @@ #include "config/feature.h" #include "io/ledstrip.h" -void targetApplyDefaultLedStripConfig(ledConfig_t *ledConfigs) +void targetApplyDefaultLedStripConfig(ledConfig_t *ledConfigs) { const ledConfig_t defaultLedStripConfig[] = { DEFINE_LED( 0, 0, 6, LD(WEST), LF(COLOR), LO(WARNING), 0 ), @@ -62,7 +62,7 @@ void targetConfiguration(master_t *config) config->flight3DConfig.deadband3d_high = 1514; config->flight3DConfig.neutral3d = 1460; config->flight3DConfig.deadband3d_throttle = 0; - + config->failsafeConfig.failsafe_procedure = 1; config->failsafeConfig.failsafe_throttle_low_delay = 10; diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index a1f8ec5eb..18717103c 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -1267,7 +1267,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand) } else { serialConfig()->portConfigs[SERIALRX_UART].functionMask = FUNCTION_NONE; } -#endif +#endif break; case BST_SET_BOARD_ALIGNMENT: boardAlignment()->rollDegrees = bstRead16(); diff --git a/src/main/target/ELLE0/target.h b/src/main/target/ELLE0/target.h index cbe277a93..4ff313a11 100644 --- a/src/main/target/ELLE0/target.h +++ b/src/main/target/ELLE0/target.h @@ -63,8 +63,8 @@ /* RX1 */ #define USE_UART2 -#define UART2_RX_PIN PA3 -#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 /* I2C */ #define USE_UART3 @@ -92,7 +92,7 @@ #define DEFAULT_FEATURES (FEATURE_VBAT) #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 +#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 #define SERIALRX_UART SERIAL_PORT_USART2 #define RX_CHANNELS_TAER diff --git a/src/main/target/FISHDRONEF4/target.c b/src/main/target/FISHDRONEF4/target.c index 299ecdc2e..4219e6809 100644 --- a/src/main/target/FISHDRONEF4/target.c +++ b/src/main/target/FISHDRONEF4/target.c @@ -25,12 +25,12 @@ #include "drivers/timer_def.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN + DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S1_OUT - DMA1_ST7 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT - DMA1_ST1 - DEF_TIM(TIM2, CH1, PA15,TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S3_OUT - DMA1_ST5 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S4_OUT - DMA1_ST6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT - DMA1_ST1 + DEF_TIM(TIM2, CH1, PA15,TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S3_OUT - DMA1_ST5 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S4_OUT - DMA1_ST6 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2 }; diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h index c83dde617..08f693d2a 100644 --- a/src/main/target/FISHDRONEF4/target.h +++ b/src/main/target/FISHDRONEF4/target.h @@ -75,8 +75,8 @@ #define USE_SPI_DEVICE_2 #define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PC3 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 #define OSD #define USE_MAX7456 diff --git a/src/main/target/KIWIF4/target.c b/src/main/target/KIWIF4/target.c index d5327d97d..add381e33 100644 --- a/src/main/target/KIWIF4/target.c +++ b/src/main/target/KIWIF4/target.c @@ -25,9 +25,9 @@ #include "drivers/timer_def.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 1), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 1), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h index 6007db44c..46b3fb28e 100644 --- a/src/main/target/KIWIF4/target.h +++ b/src/main/target/KIWIF4/target.h @@ -50,8 +50,8 @@ #define OSD #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI2 -#define MAX7456_SPI_CS_PIN PB12 +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN PB12 //#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5 //#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0 //#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER diff --git a/src/main/target/NAZE/initialisation.c b/src/main/target/NAZE/initialisation.c index 9ff56b1f6..9b121e4b1 100644 --- a/src/main/target/NAZE/initialisation.c +++ b/src/main/target/NAZE/initialisation.c @@ -39,6 +39,6 @@ void targetBusInit(void) if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) { serialRemovePort(SERIAL_PORT_USART3); i2cInit(I2C_DEVICE); - } + } } } \ No newline at end of file diff --git a/src/main/target/NERO/target.h b/src/main/target/NERO/target.h index 0cbc06048..bd68b2db2 100644 --- a/src/main/target/NERO/target.h +++ b/src/main/target/NERO/target.h @@ -18,7 +18,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "NERO" -#define CONFIG_START_FLASH_ADDRESS (0x08060000) +#define CONFIG_START_FLASH_ADDRESS (0x08060000) #define USBD_PRODUCT_STRING "NERO" diff --git a/src/main/target/RG_SSD_F3/target.c b/src/main/target/RG_SSD_F3/target.c index 477472a8d..67f27ff56 100644 --- a/src/main/target/RG_SSD_F3/target.c +++ b/src/main/target/RG_SSD_F3/target.c @@ -9,15 +9,15 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED) , + DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED) , // Main outputs 6 PWM - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), - DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), - DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), - // Additional outputs - DEF_TIM(TIM16,CH1, PA6, TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), - DEF_TIM(TIM1 ,CH1N,PA7, TIM_USE_LED, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), + // Additional outputs + DEF_TIM(TIM16,CH1, PA6, TIM_USE_TRANSPONDER, TIMER_OUTPUT_ENABLED), + DEF_TIM(TIM1 ,CH1N,PA7, TIM_USE_LED, TIMER_OUTPUT_ENABLED), }; diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h index 017e5ceee..dd69677d5 100644 --- a/src/main/target/RG_SSD_F3/target.h +++ b/src/main/target/RG_SSD_F3/target.h @@ -96,7 +96,7 @@ #define UART4_TX_PIN PC10 #define UART4_RX_PIN PC11 #define UART5_TX_PIN PC12 -#define UART5_RX_PIN PD2 +#define UART5_RX_PIN PD2 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA14/AF4), SCL (PA15/AF4) diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index 7b9cb1ef4..731856bf7 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -28,7 +28,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { #ifdef TINYBEEF3 // PPM / UART2 RX DEF_TIM(TIM8, CH1, PA15, TIM_USE_PPM, 0 ), // PPM - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 1 ), // PWM1 + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 1 ), // PWM1 DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, 1 ), // PWM2 DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1 ), // PWM3 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1 ), // PWM4 diff --git a/src/main/target/TINYFISH/config.c b/src/main/target/TINYFISH/config.c index 2812a1d7a..51834b778 100644 --- a/src/main/target/TINYFISH/config.c +++ b/src/main/target/TINYFISH/config.c @@ -46,7 +46,7 @@ void targetConfiguration(master_t *config) // we use the same uart for frsky telemetry and SBUS, both non inverted int index = findSerialPortIndexByIdentifier(SBUS_TELEMETRY_UART); config->serialConfig.portConfigs[index].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL; - + config->rxConfig.serialrx_provider = SERIALRX_SBUS; config->telemetryConfig.telemetry_inversion = 0; config->rxConfig.sbus_inversion = 0; diff --git a/src/main/target/TINYFISH/target.h b/src/main/target/TINYFISH/target.h index e47e42b23..54954dd0a 100644 --- a/src/main/target/TINYFISH/target.h +++ b/src/main/target/TINYFISH/target.h @@ -57,14 +57,14 @@ #define USE_UART2 #define USE_UART3 -#define UART1_TX_PIN PB6 -#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PA14 +#define UART2_TX_PIN PA14 #define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 -#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define SBUS_TELEMETRY_UART SERIAL_PORT_USART2 @@ -77,7 +77,7 @@ #define SPI1_MOSI_PIN PA7 #define USE_SPI -#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_2 #define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 @@ -108,7 +108,7 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_TELEMETRY) -#define TARGET_CONFIG +#define TARGET_CONFIG #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/telemetry/ibus.c b/src/main/telemetry/ibus.c index 52b91c838..b18c29cb6 100644 --- a/src/main/telemetry/ibus.c +++ b/src/main/telemetry/ibus.c @@ -50,7 +50,7 @@ #include "fc/rc_controls.h" #include "scheduler/scheduler.h" -#include "telemetry/telemetry.h" +#include "telemetry/telemetry.h" #include "telemetry/ibus.h" /* @@ -197,7 +197,7 @@ typedef enum { IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE = 0x03 } ibusSensorType_e; -/* Address lookup relative to the sensor base address which is the lowest address seen by the FC +/* Address lookup relative to the sensor base address which is the lowest address seen by the FC The actual lowest value is likely to change when sensors are daisy chained */ static const uint8_t sensorAddressTypeLookup[] = { IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE, @@ -285,7 +285,7 @@ static ibusAddress_t getAddress(const uint8_t *ibusPacket) static void dispatchMeasurementReply(ibusAddress_t address) { int value; - + switch (sensorAddressTypeLookup[address - ibusBaseAddress]) { case IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE: value = getVbat() * 10; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index d7d57cd0b..2d360c454 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -325,15 +325,15 @@ void configureSmartPortTelemetryPort(void) } portOptions_t portOptions = 0; - + if (telemetryConfig->sportHalfDuplex) { portOptions |= SERIAL_BIDIR; } - + if (telemetryConfig->telemetry_inversion) { portOptions |= SERIAL_INVERTED; } - + smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions); if (!smartPortSerialPort) {