remove not needed whitespaces

This commit is contained in:
Steffen Windoffer 2017-08-24 11:29:11 +02:00
parent dfe868ef96
commit 03aa31acdd
197 changed files with 118 additions and 308 deletions

View File

@ -11,5 +11,3 @@ Please search for existing issues *before* creating new ones.
# Developers
Please refer to the development section in the `docs/development` folder.

View File

@ -19,4 +19,3 @@ export V0 :=
export V1 :=
export STDOUT :=
endif

View File

@ -15,4 +15,3 @@ endif
ifneq ($(OPENOCD_CFG),)
OPENOCD_COMMAND = $(OPENOCD) -f $(OPENOCD_IF) -f $(OPENOCD_CFG)
endif

View File

@ -344,4 +344,3 @@ breakpad_clean:
$(V1) [ ! -d "$(BREAKPAD_DIR)" ] || $(RM) -rf $(BREAKPAD_DIR)
$(V0) @echo " CLEAN $(BREAKPAD_DL_FILE)"
$(V1) $(RM) -f $(BREAKPAD_DL_FILE)

View File

@ -38,4 +38,3 @@
#define REQUIRE_CC_ARM_PRINTF_SUPPORT
#define REQUIRE_PRINTF_LONG_SUPPORT
#endif

View File

@ -25,4 +25,3 @@ void cmsUpdate(uint32_t currentTimeUs);
#define CMS_EXIT (0)
#define CMS_EXIT_SAVE (1)
#define CMS_EXIT_SAVEREBOOT (2)

View File

@ -100,4 +100,3 @@ CMS_Menu cmsx_menuVtxRTC6705 = {
};
#endif // CMS

View File

@ -36,4 +36,3 @@ void bitArrayClr(void *array, unsigned bit)
{
BITARRAY_BIT_OP((uint32_t*)array, bit, &=~);
}

View File

@ -81,4 +81,3 @@ rgbColor24bpp_t* hsvToRgb24(const hsvColor_t* c)
}
return &r;
}

View File

@ -286,4 +286,3 @@ float firFilterDenoiseUpdate(firFilterDenoise_t *filter, float input)
else
return filter->movingSum / ++filter->filledCount + 1;
}

View File

@ -98,4 +98,3 @@ float firFilterLastInput(const firFilter_t *filter);
void firFilterDenoiseInit(firFilterDenoise_t *filter, uint8_t gyroSoftLpfHz, uint16_t targetLooptime);
float firFilterDenoiseUpdate(firFilterDenoise_t *filter, float input);

View File

@ -282,4 +282,3 @@ const huffmanTable_t huffmanTable[HUFFMAN_TABLE_SIZE] = {
{ 9, 0x2800 }, // 0xFF 001010000
{ 12, 0x0000 }, // EOF 000000000000
};

View File

@ -282,4 +282,3 @@ float fastA2F(const char *p)
// Return signed and scaled floating point result.
return sign * (frac ? (value / scale) : (value * scale));
}

View File

@ -95,4 +95,3 @@ int32_t unittest_pidMultiWiiRewrite_DTerm[3];
#endif // UNIT_TEST
#endif // SRC_MAIN_FLIGHT_PID_C_

View File

@ -125,4 +125,3 @@
#define PG_RESERVED_FOR_TESTING_1 4095
#define PG_RESERVED_FOR_TESTING_2 4094
#define PG_RESERVED_FOR_TESTING_3 4093

View File

@ -1,10 +0,0 @@
/*
* accMpu6000.cpp
*
* Created on: 31 Mar 2017
* Author: martinbudden
*/

View File

@ -151,4 +151,3 @@ bool fakeAccDetect(accDev_t *acc)
return true;
}
#endif // USE_FAKE_ACC

View File

@ -439,4 +439,3 @@ typedef struct {
bool lsm303dlhcAccDetect(accDev_t *acc);

View File

@ -236,4 +236,3 @@ void adcInit(const adcConfig_t *config)
ADC_StartConversion(adc.ADCx);
}

View File

@ -57,4 +57,3 @@
// 10/16 = 0.625 ms
bool bmp280Detect(baroDev_t *baro);

View File

@ -70,4 +70,3 @@ bool fakeBaroDetect(baroDev_t *baro)
return true;
}
#endif // USE_FAKE_BARO

View File

@ -20,4 +20,3 @@
struct baroDev_s;
bool fakeBaroDetect(struct baroDev_s *baro);
void fakeBaroSet(int32_t pressure, int32_t temperature);

View File

@ -50,4 +50,3 @@ void targetBusInit(void);
bool busWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
bool busReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length);
uint8_t busReadRegister(const busDevice_t *bus, uint8_t reg);

View File

@ -264,4 +264,3 @@ uint16_t i2cGetErrorCounter(void)
}
#endif

View File

@ -70,4 +70,3 @@ typedef struct SPIDevice_s {
} spiDevice_t;
extern spiDevice_t spiDevice[SPIDEV_COUNT];

View File

@ -63,4 +63,3 @@ bool fakeMagDetect(magDev_t *mag)
return true;
}
#endif // USE_FAKE_MAG

View File

@ -115,4 +115,3 @@ void displayInit(displayPort_t *instance, const displayPortVTable_t *vTable)
instance->grabCount = 0;
instance->cursorRow = -1;
}

View File

@ -49,4 +49,3 @@
#include "target.h"
// include template-generated macros for IO pins
#include "io_def_generated.h"

View File

@ -1160,4 +1160,3 @@
# define DEFIO_PORT_USED_LIST /* empty */
# define DEFIO_PORT_OFFSET_LIST /* empty */
#endif

View File

@ -18,4 +18,3 @@ enum rcc_reg {
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);

View File

@ -1,4 +1,3 @@
#pragma once
typedef uint8_t rccPeriphTag_t;

View File

@ -67,4 +67,3 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"ESCSERIAL",
"CAMERA_CONTROL",
};

View File

@ -198,4 +198,3 @@ void NRF24L01_SetTxMode(void);
void NRF24L01_ClearAllInterrupts(void);
void NRF24L01_SetChannel(uint8_t channel);
bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length);

View File

@ -144,4 +144,3 @@ uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *ret
return ret;
}
#endif

View File

@ -32,4 +32,3 @@ uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data);
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length);
uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData);
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length);

View File

@ -87,4 +87,3 @@ uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr)
packet[RX_TX_ADDR_LEN + len + 1] = crc & 0xff;
return NRF24L01_WritePayload(packet, RX_TX_ADDR_LEN + len + 2);
}

View File

@ -22,4 +22,3 @@
uint16_t XN297_UnscramblePayload(uint8_t* data, int len, const uint8_t *rxAddr);
uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr);

View File

@ -33,4 +33,3 @@ uint32_t softSerialTxBytesFree(const serialPort_t *instance);
uint8_t softSerialReadByte(serialPort_t *instance);
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
bool isSoftSerialTransmitBufferEmpty(const serialPort_t *s);

View File

@ -47,4 +47,3 @@ void tcpDataOut(tcpPort_t *instance);
bool tcpIsStart(void);
bool* tcpGetUsed(void);
tcpPort_t* tcpGetPool(void);

View File

@ -39,4 +39,3 @@ typedef struct beeperDevConfig_s {
void systemBeep(bool on);
void systemBeepToggle(void);
void beeperInit(const beeperDevConfig_t *beeperDevConfig);

View File

@ -36,4 +36,3 @@ void serializeBoxPermanentIdFn(struct sbuf_s *dst, const box_t *box);
typedef void serializeBoxFn(struct sbuf_s *dst, const box_t *box);
void serializeBoxReply(struct sbuf_s *dst, int page, serializeBoxFn *serializeBox);
void initActiveBoxIds(void);

View File

@ -145,6 +145,3 @@ extern const char * const lookupTableBaroHardware[];
extern const char * const lookupTableMagHardware[];
//extern const uint8_t lookupTableMagHardwareEntryCount;

View File

@ -89,7 +89,3 @@ void failsafeOnRxResume(void);
void failsafeOnValidDataReceived(void);
void failsafeOnValidDataFailed(void);

View File

@ -528,4 +528,3 @@ void imuSetHasNewData(uint32_t dt)
IMU_UNLOCK;
}
#endif

View File

@ -80,5 +80,3 @@ void imuSetAttitudeQuat(float w, float x, float y, float z);
void imuSetHasNewData(uint32_t dt);
#endif
#endif

View File

@ -45,4 +45,3 @@ typedef struct ioMem_s {
uint8_t D_FLASH_ADDR_L;
uint8_t *D_PTR_I;
} ioMem_t;

View File

@ -24,4 +24,3 @@ uint8_t Stk_WriteEEprom(ioMem_t *pMem);
uint8_t Stk_ReadFlash(ioMem_t *pMem);
uint8_t Stk_WriteFlash(ioMem_t *pMem);
uint8_t Stk_Chip_Erase(void);

View File

@ -16,4 +16,3 @@
*/
#pragma once

View File

@ -83,5 +83,3 @@ void warningLedUpdate(void)
warningLedRefresh();
}

View File

@ -42,4 +42,3 @@ extern const char * const rtc6705PowerNames[RTC6705_POWER_COUNT];
void vtxRTC6705Configure(void);
bool vtxRTC6705Init();

View File

@ -316,4 +316,3 @@
#define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
#define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
#define MSP_SET_4WAY_IF 245 //in message Sets 4way interface

View File

@ -18,4 +18,3 @@
#pragma once
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);

View File

@ -300,4 +300,3 @@ void cx10Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
cx10Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
}
#endif

View File

@ -25,4 +25,3 @@ struct rxRuntimeConfig_s;
void cx10Nrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload);

View File

@ -425,4 +425,3 @@ void inavNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
inavNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol, &rxConfig->rx_spi_id, rxConfig->rx_spi_rf_channel_count);
}
#endif

View File

@ -300,4 +300,3 @@ void symaNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
symaNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
}
#endif

View File

@ -64,4 +64,3 @@ void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
}
}
#endif

View File

@ -384,4 +384,3 @@ bool srxlRxIsActive(void)
}
#endif // SERIAL_RX

View File

@ -79,4 +79,3 @@ void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims);
union flightDynamicsTrims_u;
void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse);
void setAccelerationFilter(uint16_t initialAccLpfCutHz);

View File

@ -108,4 +108,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))

View File

@ -8,4 +8,3 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c \
drivers/inverter.c

View File

@ -41,4 +41,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM10 - PA1 - DMA1_CH7 - *TIM2_CH2, TIM15_CH1N
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED ), // PPM - PA3 - DMA1_CH7 - TIM2_CH4, TIM15_CH2
};

View File

@ -131,4 +131,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View File

@ -7,4 +7,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/compass/compass_ak8963.c

View File

@ -191,4 +191,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 13
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )

View File

@ -83,4 +83,3 @@ void targetConfiguration(void)
compassConfigMutable()->mag_hardware = MAG_DEFAULT;
}
#endif

View File

@ -52,4 +52,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0),
};

View File

@ -228,4 +228,3 @@
*/
#define USABLE_TIMER_CHANNEL_COUNT 5
#define USED_TIMERS ( TIM_N(3) | TIM_N(8) | TIM_N(5) )

View File

@ -18,4 +18,3 @@
* support for CAN
* SD card logging (SPI)
* 3 AD channels, one with 10k/1k divider, two with 1k series resistor

View File

@ -8,4 +8,3 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c

View File

@ -16,4 +16,3 @@
* external SPI (shared with U4/5)
* 128Mb dataflash logging (SPI)
* Voltage measurement, with 10k/1k divider

View File

@ -43,4 +43,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, 0 ), // S8_OUT DMA2_ST6
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S9_OUT DMA1_ST4
};

View File

@ -30,4 +30,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM3 - PA8 - DMA1_CH2 - *TIM1_CH1, TIM4_ETR
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED ), // PWM4 - PB0 - DMA2_CH5 - TIM3_CH3, TIM1_CH2N, *TIM8_CH2N
};

View File

@ -117,4 +117,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 4
#define USED_TIMERS ( TIM_N(1) | TIM_N(8) | TIM_N(15) )

View File

@ -7,4 +7,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/vtx_rtc6705_soft_spi.c \
drivers/max7456.c

View File

@ -74,4 +74,3 @@ void targetPreInit(void)
IOHi(sdcardIo);
}
}

View File

@ -40,4 +40,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1) // S6_OUT
};

View File

@ -8,4 +8,3 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c

View File

@ -45,4 +45,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0), // PWM17 - PB1
DEF_TIM(TIM3, CH2, PA4, TIM_USE_PWM, 0) // PWM18 - PA4
};

View File

@ -121,4 +121,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 18
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))

View File

@ -15,4 +15,3 @@ TARGET_SRC = \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_ak8975.c

View File

@ -41,4 +41,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0 ) // PWM14 - OUT6
};

View File

@ -9,4 +9,3 @@ TARGET_SRC = \
blackbox/blackbox_io.c \
telemetry/telemetry.c \
telemetry/ltm.c

View File

@ -6,4 +6,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c

View File

@ -44,4 +44,3 @@ bool bstSlaveWrite(uint8_t* data);
void bstMasterWriteLoop(void);
void crc8Cal(uint8_t data_in);

View File

@ -133,4 +133,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))

View File

@ -47,5 +47,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// I2C
//UART3 RX: DMA1_ST1
//UART3 TX: DMA1_ST3

View File

@ -26,4 +26,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR, 1, 0), // S8_OUT
DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0), // sonar echo if needed
};

View File

@ -156,4 +156,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9))

View File

@ -5,4 +5,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_hmc5883l.c

View File

@ -7,4 +7,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/max7456.c

View File

@ -47,4 +47,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1 ), // TRANSPONDER - PA8
#endif
};

View File

@ -35,4 +35,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2_CH6
};

View File

@ -5,4 +5,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/flash_m25p16.c

View File

@ -43,4 +43,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM8 - PA3
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // GPIO_TIMER / LED_STRIP
};

View File

@ -111,4 +111,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View File

@ -6,4 +6,3 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/barometer/barometer_bmp085.c

View File

@ -44,4 +44,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, 1), // PWM8 - PA3
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 1), // GPIO_TIMER / LED_STRIP
};

View File

@ -115,5 +115,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )

View File

@ -141,4 +141,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 8
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8))

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