diff --git a/.github/issue_template.md b/.github/issue_template.md index 7c079a66be..33621e0747 100644 --- a/.github/issue_template.md +++ b/.github/issue_template.md @@ -7,5 +7,5 @@ 2.) Include ways to reproduce the problem; 3.) Provide information about your flightcontroller and other components including how they are connected/wired; 4.) Add the used configuration and firmware version; -5.) Create a `diff` and post it here in a code block. Put \`\`\` (three backticks) at the start and end of the `diff` block; and +5.) Create a `diff` and post it here in a code block. Put \`\`\` (three backticks) at the start and end of the `diff` block; and 6.) Remove this Text :). diff --git a/.travis.sh b/.travis.sh index efa5488c01..865918d69e 100755 --- a/.travis.sh +++ b/.travis.sh @@ -67,7 +67,7 @@ elif [ $TARGET ] ; then elif [ $GOAL ] ; then $MAKE $GOAL || exit $? - + if [ $PUBLISHCOV ] ; then if [ "test" == "$GOAL" ] ; then lcov --directory . -b src/test --capture --output-file coverage.info 2>&1 | grep -E ":version '402\*', prefer.*'406\*" --invert-match @@ -76,6 +76,6 @@ elif [ $GOAL ] ; then coveralls-lcov coverage.info # uploads to coveralls fi fi -else +else $MAKE all fi diff --git a/.travis.yml b/.travis.yml index 4c9ca98726..82f041a159 100644 --- a/.travis.yml +++ b/.travis.yml @@ -54,11 +54,11 @@ before_script: script: ./.travis.sh -cache: +cache: directories: - downloads - tools - + #notifications: # irc: "chat.freenode.net#cleanflight" diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index af458ab3a8..42abcacd49 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -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. - - diff --git a/Makefile b/Makefile index 7e143be7c6..1cf65c6139 100644 --- a/Makefile +++ b/Makefile @@ -106,7 +106,7 @@ FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) CSOURCES := $(shell find $(SRC_DIR) -name '*.c') -LD_FLAGS := +LD_FLAGS := # # Default Tool options - can be overridden in {mcu}.mk files. diff --git a/README.md b/README.md index 2fa791e7e7..a5f0b30909 100644 --- a/README.md +++ b/README.md @@ -27,7 +27,7 @@ Betaflight has the following features: ## Installation & Documentation -See: https://github.com/betaflight/betaflight/wiki +See: https://github.com/betaflight/betaflight/wiki ## IRC Support and Developers Channel @@ -89,18 +89,18 @@ Origins for this fork (Thanks!): * **Dominic Clifton** (for Cleanflight), and * **Sambas** (for the original STM32F4 port). -The Betaflight Configurator is forked from Cleanflight Configurator and its origins. +The Betaflight Configurator is forked from Cleanflight Configurator and its origins. Origins for Betaflight Configurator: * **Dominic Clifton** (for Cleanflight configurator), and -* **ctn** (for the original Configurator). +* **ctn** (for the original Configurator). Big thanks to current and past contributors: * Budden, Martin (martinbudden) * Bardwell, Joshua (joshuabardwell) * Blackman, Jason (blckmn) * ctzsnooze -* Höglund, Anders (andershoglund) +* Höglund, Anders (andershoglund) * Ledvin, Peter (ledvinap) - **IO code awesomeness!** * kc10kevin * Keeble, Gary (MadmanK) diff --git a/make/build_verbosity.mk b/make/build_verbosity.mk index e764554a57..9d2f5dc3f3 100644 --- a/make/build_verbosity.mk +++ b/make/build_verbosity.mk @@ -19,4 +19,3 @@ export V0 := export V1 := export STDOUT := endif - diff --git a/make/mcu/SITL.mk b/make/mcu/SITL.mk index 04e98ba5a2..242b42450e 100644 --- a/make/mcu/SITL.mk +++ b/make/mcu/SITL.mk @@ -66,4 +66,4 @@ OPTIMISE_SPEED := -Ofast OPTIMISE_SIZE := -Os LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) -endif \ No newline at end of file +endif diff --git a/make/mcu/STM32F1.mk b/make/mcu/STM32F1.mk index 99cc14eb29..b952900d53 100644 --- a/make/mcu/STM32F1.mk +++ b/make/mcu/STM32F1.mk @@ -69,12 +69,12 @@ MCU_COMMON_SRC = \ drivers/system_stm32f10x.c \ drivers/timer_stm32f10x.c -DSP_LIB := +DSP_LIB := ifneq ($(DEBUG),GDB) OPTIMISE_DEFAULT := -Os -OPTIMISE_SPEED := -OPTIMISE_SIZE := +OPTIMISE_SPEED := +OPTIMISE_SIZE := LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) endif diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk index 2ea947be23..18cf321dfe 100644 --- a/make/mcu/STM32F4.mk +++ b/make/mcu/STM32F4.mk @@ -17,7 +17,7 @@ ifeq ($(PERIPH_DRIVER), HAL) CMSIS_DIR := $(ROOT)/lib/main/STM32F4/Drivers/CMSIS STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_HAL_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c)) -EXCLUDES = +EXCLUDES = else CMSIS_DIR := $(ROOT)/lib/main/CMSIS/CM4 STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver @@ -102,7 +102,7 @@ VPATH := $(VPATH):$(CMSIS_DIR)/CoreSupport:$(CMSIS_DIR)/DeviceSupport/ VPATH := $(VPATH):$(CMSIS_DIR)/Core:$(CMSIS_DIR)/Device/ST/STM32F4xx ifeq ($(PERIPH_DRIVER), HAL) -CMSIS_SRC := +CMSIS_SRC := INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(STDPERIPH_DIR)/Inc \ $(USBCORE_DIR)/Inc \ diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk index 2e1dd9d415..564583c55c 100644 --- a/make/mcu/STM32F7.mk +++ b/make/mcu/STM32F7.mk @@ -94,7 +94,7 @@ DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ #CMSIS VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx VPATH := $(VPATH):$(STDPERIPH_DIR)/Src -CMSIS_SRC := +CMSIS_SRC := INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(STDPERIPH_DIR)/Inc \ $(USBCORE_DIR)/Inc \ @@ -114,7 +114,7 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fs DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS))) -DEVICE_FLAGS += -DSTM32F745xx +DEVICE_FLAGS += -DSTM32F745xx LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld STARTUP_SRC = startup_stm32f745xx.s TARGET_FLASH := 2048 diff --git a/make/openocd.mk b/make/openocd.mk index 911c294d4e..3aaca8c602 100644 --- a/make/openocd.mk +++ b/make/openocd.mk @@ -15,4 +15,3 @@ endif ifneq ($(OPENOCD_CFG),) OPENOCD_COMMAND = $(OPENOCD) -f $(OPENOCD_IF) -f $(OPENOCD_CFG) endif - diff --git a/make/source.mk b/make/source.mk index 7431e42eba..c668bbc113 100644 --- a/make/source.mk +++ b/make/source.mk @@ -167,7 +167,7 @@ FC_SRC = \ io/vtx_smartaudio.c \ io/vtx_tramp.c \ io/vtx_control.c - + COMMON_DEVICE_SRC = \ $(CMSIS_SRC) \ $(DEVICE_STDPERIPH_SRC) diff --git a/make/tools.mk b/make/tools.mk index 86f3fbeeb2..142270fe2c 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -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) - diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index 56f82ddb5f..e8f91cbc4e 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -38,4 +38,3 @@ #define REQUIRE_CC_ARM_PRINTF_SUPPORT #define REQUIRE_PRINTF_LONG_SUPPORT #endif - diff --git a/src/main/cms/cms.h b/src/main/cms/cms.h index aeafdda0e7..80f37b68ed 100644 --- a/src/main/cms/cms.h +++ b/src/main/cms/cms.h @@ -25,4 +25,3 @@ void cmsUpdate(uint32_t currentTimeUs); #define CMS_EXIT (0) #define CMS_EXIT_SAVE (1) #define CMS_EXIT_SAVEREBOOT (2) - diff --git a/src/main/cms/cms_menu_vtx_rtc6705.c b/src/main/cms/cms_menu_vtx_rtc6705.c index 5b12bd1eb1..cf9a2b1293 100644 --- a/src/main/cms/cms_menu_vtx_rtc6705.c +++ b/src/main/cms/cms_menu_vtx_rtc6705.c @@ -100,4 +100,3 @@ CMS_Menu cmsx_menuVtxRTC6705 = { }; #endif // CMS - diff --git a/src/main/common/bitarray.c b/src/main/common/bitarray.c index 53ca99127c..41a5b48761 100644 --- a/src/main/common/bitarray.c +++ b/src/main/common/bitarray.c @@ -36,4 +36,3 @@ void bitArrayClr(void *array, unsigned bit) { BITARRAY_BIT_OP((uint32_t*)array, bit, &=~); } - diff --git a/src/main/common/colorconversion.c b/src/main/common/colorconversion.c index a37bc821ab..02b360f2b0 100644 --- a/src/main/common/colorconversion.c +++ b/src/main/common/colorconversion.c @@ -81,4 +81,3 @@ rgbColor24bpp_t* hsvToRgb24(const hsvColor_t* c) } return &r; } - diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 847552dffc..2351e4ad94 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -286,4 +286,3 @@ float firFilterDenoiseUpdate(firFilterDenoise_t *filter, float input) else return filter->movingSum / ++filter->filledCount + 1; } - diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 9287a55287..4033469e75 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -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); - diff --git a/src/main/common/huffman_table.c b/src/main/common/huffman_table.c index c93111030f..d0654e8a3a 100644 --- a/src/main/common/huffman_table.c +++ b/src/main/common/huffman_table.c @@ -282,4 +282,3 @@ const huffmanTable_t huffmanTable[HUFFMAN_TABLE_SIZE] = { { 9, 0x2800 }, // 0xFF 001010000 { 12, 0x0000 }, // EOF 000000000000 }; - diff --git a/src/main/common/typeconversion.c b/src/main/common/typeconversion.c index 9c2ffcc733..f7e952f183 100644 --- a/src/main/common/typeconversion.c +++ b/src/main/common/typeconversion.c @@ -282,4 +282,3 @@ float fastA2F(const char *p) // Return signed and scaled floating point result. return sign * (frac ? (value / scale) : (value * scale)); } - diff --git a/src/main/config/config_unittest.h b/src/main/config/config_unittest.h index e32015734c..a15d8876fa 100644 --- a/src/main/config/config_unittest.h +++ b/src/main/config/config_unittest.h @@ -95,4 +95,3 @@ int32_t unittest_pidMultiWiiRewrite_DTerm[3]; #endif // UNIT_TEST #endif // SRC_MAIN_FLIGHT_PID_C_ - diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 3b3e47676e..c1475298f5 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -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 - diff --git a/src/main/drivers/accgyro/accMpu6000.cpp b/src/main/drivers/accgyro/accMpu6000.cpp deleted file mode 100644 index c449af5df4..0000000000 --- a/src/main/drivers/accgyro/accMpu6000.cpp +++ /dev/null @@ -1,10 +0,0 @@ -/* - * accMpu6000.cpp - * - * Created on: 31 Mar 2017 - * Author: martinbudden - */ - - - - diff --git a/src/main/drivers/accgyro/accgyro_fake.c b/src/main/drivers/accgyro/accgyro_fake.c index 819d739a36..eb4d2f6b76 100644 --- a/src/main/drivers/accgyro/accgyro_fake.c +++ b/src/main/drivers/accgyro/accgyro_fake.c @@ -151,4 +151,3 @@ bool fakeAccDetect(accDev_t *acc) return true; } #endif // USE_FAKE_ACC - diff --git a/src/main/drivers/accgyro/accgyro_lsm303dlhc.h b/src/main/drivers/accgyro/accgyro_lsm303dlhc.h index 08e85ff44c..e3a5bb7067 100644 --- a/src/main/drivers/accgyro/accgyro_lsm303dlhc.h +++ b/src/main/drivers/accgyro/accgyro_lsm303dlhc.h @@ -439,4 +439,3 @@ typedef struct { bool lsm303dlhcAccDetect(accDev_t *acc); - diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 04e0802f24..619de861d2 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -236,4 +236,3 @@ void adcInit(const adcConfig_t *config) ADC_StartConversion(adc.ADCx); } - diff --git a/src/main/drivers/barometer/barometer_bmp280.h b/src/main/drivers/barometer/barometer_bmp280.h index ee8368b364..0802e775aa 100644 --- a/src/main/drivers/barometer/barometer_bmp280.h +++ b/src/main/drivers/barometer/barometer_bmp280.h @@ -57,4 +57,3 @@ // 10/16 = 0.625 ms bool bmp280Detect(baroDev_t *baro); - diff --git a/src/main/drivers/barometer/barometer_fake.c b/src/main/drivers/barometer/barometer_fake.c index 0d563f3add..07e5f2283f 100644 --- a/src/main/drivers/barometer/barometer_fake.c +++ b/src/main/drivers/barometer/barometer_fake.c @@ -70,4 +70,3 @@ bool fakeBaroDetect(baroDev_t *baro) return true; } #endif // USE_FAKE_BARO - diff --git a/src/main/drivers/barometer/barometer_fake.h b/src/main/drivers/barometer/barometer_fake.h index bdf67ed24c..d189dcf23e 100644 --- a/src/main/drivers/barometer/barometer_fake.h +++ b/src/main/drivers/barometer/barometer_fake.h @@ -20,4 +20,3 @@ struct baroDev_s; bool fakeBaroDetect(struct baroDev_s *baro); void fakeBaroSet(int32_t pressure, int32_t temperature); - diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index 448e5b53fb..2ca515dd85 100644 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -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); - diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c index 938a295632..34e2887ef3 100644 --- a/src/main/drivers/bus_i2c_soft.c +++ b/src/main/drivers/bus_i2c_soft.c @@ -264,4 +264,3 @@ uint16_t i2cGetErrorCounter(void) } #endif - diff --git a/src/main/drivers/bus_spi_impl.h b/src/main/drivers/bus_spi_impl.h index 58dab324ec..fe9ed35598 100644 --- a/src/main/drivers/bus_spi_impl.h +++ b/src/main/drivers/bus_spi_impl.h @@ -70,4 +70,3 @@ typedef struct SPIDevice_s { } spiDevice_t; extern spiDevice_t spiDevice[SPIDEV_COUNT]; - diff --git a/src/main/drivers/compass/compass_fake.c b/src/main/drivers/compass/compass_fake.c index cb8098c77d..67532a074b 100644 --- a/src/main/drivers/compass/compass_fake.c +++ b/src/main/drivers/compass/compass_fake.c @@ -63,4 +63,3 @@ bool fakeMagDetect(magDev_t *mag) return true; } #endif // USE_FAKE_MAG - diff --git a/src/main/drivers/display.c b/src/main/drivers/display.c index 978663fd6a..7590641aa3 100644 --- a/src/main/drivers/display.c +++ b/src/main/drivers/display.c @@ -115,4 +115,3 @@ void displayInit(displayPort_t *instance, const displayPortVTable_t *vTable) instance->grabCount = 0; instance->cursorRow = -1; } - diff --git a/src/main/drivers/dma_stm32f7xx.c b/src/main/drivers/dma_stm32f7xx.c index d1da2519e9..c1e6667046 100644 --- a/src/main/drivers/dma_stm32f7xx.c +++ b/src/main/drivers/dma_stm32f7xx.c @@ -115,4 +115,4 @@ dmaIdentifier_e dmaGetIdentifier(const DMA_Stream_TypeDef* stream) } } return 0; -} \ No newline at end of file +} diff --git a/src/main/drivers/io_def.h b/src/main/drivers/io_def.h index a200f4af40..add80273c3 100644 --- a/src/main/drivers/io_def.h +++ b/src/main/drivers/io_def.h @@ -49,4 +49,3 @@ #include "target.h" // include template-generated macros for IO pins #include "io_def_generated.h" - diff --git a/src/main/drivers/io_def_generated.h b/src/main/drivers/io_def_generated.h index c99ba92651..cb853920a7 100644 --- a/src/main/drivers/io_def_generated.h +++ b/src/main/drivers/io_def_generated.h @@ -1160,4 +1160,3 @@ # define DEFIO_PORT_USED_LIST /* empty */ # define DEFIO_PORT_OFFSET_LIST /* empty */ #endif - diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h index 6c1384ff3d..d074960e1d 100644 --- a/src/main/drivers/rcc.h +++ b/src/main/drivers/rcc.h @@ -18,4 +18,3 @@ enum rcc_reg { void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState); void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState); - diff --git a/src/main/drivers/rcc_types.h b/src/main/drivers/rcc_types.h index 1b7d7b9f2f..eaf4549d6e 100644 --- a/src/main/drivers/rcc_types.h +++ b/src/main/drivers/rcc_types.h @@ -1,4 +1,3 @@ #pragma once typedef uint8_t rccPeriphTag_t; - diff --git a/src/main/drivers/resource.c b/src/main/drivers/resource.c index 13953e3189..f88150c695 100644 --- a/src/main/drivers/resource.c +++ b/src/main/drivers/resource.c @@ -67,4 +67,3 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = { "ESCSERIAL", "CAMERA_CONTROL", }; - diff --git a/src/main/drivers/rx_nrf24l01.h b/src/main/drivers/rx_nrf24l01.h index 27d3c65cb7..b0453d16d5 100644 --- a/src/main/drivers/rx_nrf24l01.h +++ b/src/main/drivers/rx_nrf24l01.h @@ -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); - diff --git a/src/main/drivers/rx_spi.c b/src/main/drivers/rx_spi.c index 33dd50e12e..3b79fb6b1b 100644 --- a/src/main/drivers/rx_spi.c +++ b/src/main/drivers/rx_spi.c @@ -144,4 +144,3 @@ uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *ret return ret; } #endif - diff --git a/src/main/drivers/rx_spi.h b/src/main/drivers/rx_spi.h index 0afd720fcb..37e453bf5f 100644 --- a/src/main/drivers/rx_spi.h +++ b/src/main/drivers/rx_spi.h @@ -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); - diff --git a/src/main/drivers/rx_xn297.c b/src/main/drivers/rx_xn297.c index dccf39ba21..c17c812c08 100644 --- a/src/main/drivers/rx_xn297.c +++ b/src/main/drivers/rx_xn297.c @@ -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); } - diff --git a/src/main/drivers/rx_xn297.h b/src/main/drivers/rx_xn297.h index 167b2f380b..73967144ba 100644 --- a/src/main/drivers/rx_xn297.h +++ b/src/main/drivers/rx_xn297.h @@ -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); - diff --git a/src/main/drivers/serial_softserial.h b/src/main/drivers/serial_softserial.h index bee1b0417c..4bdeaa0587 100644 --- a/src/main/drivers/serial_softserial.h +++ b/src/main/drivers/serial_softserial.h @@ -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); - diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h index c7f26a3d10..07e4e54447 100644 --- a/src/main/drivers/serial_tcp.h +++ b/src/main/drivers/serial_tcp.h @@ -47,4 +47,3 @@ void tcpDataOut(tcpPort_t *instance); bool tcpIsStart(void); bool* tcpGetUsed(void); tcpPort_t* tcpGetPool(void); - diff --git a/src/main/drivers/sound_beeper.h b/src/main/drivers/sound_beeper.h index e2b2a24788..e119aabf5f 100644 --- a/src/main/drivers/sound_beeper.h +++ b/src/main/drivers/sound_beeper.h @@ -39,4 +39,3 @@ typedef struct beeperDevConfig_s { void systemBeep(bool on); void systemBeepToggle(void); void beeperInit(const beeperDevConfig_t *beeperDevConfig); - diff --git a/src/main/fc/fc_msp_box.h b/src/main/fc/fc_msp_box.h index c1497a7409..3cd5d927c3 100644 --- a/src/main/fc/fc_msp_box.h +++ b/src/main/fc/fc_msp_box.h @@ -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); - diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index f543210cb2..6dcf5d37f0 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -145,6 +145,3 @@ extern const char * const lookupTableBaroHardware[]; extern const char * const lookupTableMagHardware[]; //extern const uint8_t lookupTableMagHardwareEntryCount; - - - diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 3b2936bb8e..581fe287ac 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -89,7 +89,3 @@ void failsafeOnRxResume(void); void failsafeOnValidDataReceived(void); void failsafeOnValidDataFailed(void); - - - - diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index d00e0c0789..a8ed94a0b0 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -528,4 +528,3 @@ void imuSetHasNewData(uint32_t dt) IMU_UNLOCK; } #endif - diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 25f84b67f0..cab4109b69 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -80,5 +80,3 @@ void imuSetAttitudeQuat(float w, float x, float y, float z); void imuSetHasNewData(uint32_t dt); #endif #endif - - diff --git a/src/main/io/serial_4way_impl.h b/src/main/io/serial_4way_impl.h index fd0ce1051e..49e3fca599 100644 --- a/src/main/io/serial_4way_impl.h +++ b/src/main/io/serial_4way_impl.h @@ -45,4 +45,3 @@ typedef struct ioMem_s { uint8_t D_FLASH_ADDR_L; uint8_t *D_PTR_I; } ioMem_t; - diff --git a/src/main/io/serial_4way_stk500v2.h b/src/main/io/serial_4way_stk500v2.h index 80ca89826d..39ec7346bc 100644 --- a/src/main/io/serial_4way_stk500v2.h +++ b/src/main/io/serial_4way_stk500v2.h @@ -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); - diff --git a/src/main/io/servos.h b/src/main/io/servos.h index dd9f1aa1ca..e563a48c45 100644 --- a/src/main/io/servos.h +++ b/src/main/io/servos.h @@ -16,4 +16,3 @@ */ #pragma once - diff --git a/src/main/io/statusindicator.c b/src/main/io/statusindicator.c index ab05ee7585..1bacf6966d 100644 --- a/src/main/io/statusindicator.c +++ b/src/main/io/statusindicator.c @@ -83,5 +83,3 @@ void warningLedUpdate(void) warningLedRefresh(); } - - diff --git a/src/main/io/vtx_rtc6705.h b/src/main/io/vtx_rtc6705.h index 47dd336d8d..9a48a8aa03 100644 --- a/src/main/io/vtx_rtc6705.h +++ b/src/main/io/vtx_rtc6705.h @@ -42,4 +42,3 @@ extern const char * const rtc6705PowerNames[RTC6705_POWER_COUNT]; void vtxRTC6705Configure(void); bool vtxRTC6705Init(); - diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h index 2529346f2a..4deda31f51 100644 --- a/src/main/msp/msp_protocol.h +++ b/src/main/msp/msp_protocol.h @@ -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 - diff --git a/src/main/rx/jetiexbus.h b/src/main/rx/jetiexbus.h index 9fe45e12e1..4622c7a4d4 100644 --- a/src/main/rx/jetiexbus.h +++ b/src/main/rx/jetiexbus.h @@ -18,4 +18,3 @@ #pragma once bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); - diff --git a/src/main/rx/nrf24_cx10.c b/src/main/rx/nrf24_cx10.c index 318f02853e..f51dba595a 100644 --- a/src/main/rx/nrf24_cx10.c +++ b/src/main/rx/nrf24_cx10.c @@ -300,4 +300,3 @@ void cx10Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi cx10Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol); } #endif - diff --git a/src/main/rx/nrf24_cx10.h b/src/main/rx/nrf24_cx10.h index 8af1547333..408e7845dc 100644 --- a/src/main/rx/nrf24_cx10.h +++ b/src/main/rx/nrf24_cx10.h @@ -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); - diff --git a/src/main/rx/nrf24_inav.c b/src/main/rx/nrf24_inav.c index c3ba65326d..3c791c4374 100644 --- a/src/main/rx/nrf24_inav.c +++ b/src/main/rx/nrf24_inav.c @@ -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 - diff --git a/src/main/rx/nrf24_syma.c b/src/main/rx/nrf24_syma.c index 2d0cdc3fdf..cd3498b288 100644 --- a/src/main/rx/nrf24_syma.c +++ b/src/main/rx/nrf24_syma.c @@ -300,4 +300,3 @@ void symaNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi symaNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol); } #endif - diff --git a/src/main/rx/pwm.c b/src/main/rx/pwm.c index d7b1d5c50a..a805ac0f08 100644 --- a/src/main/rx/pwm.c +++ b/src/main/rx/pwm.c @@ -64,4 +64,3 @@ void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) } } #endif - diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 0119fca5bf..5d4bad4ec6 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -384,4 +384,3 @@ bool srxlRxIsActive(void) } #endif // SERIAL_RX - diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index 38f6c5fa70..b211abbb65 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -79,4 +79,3 @@ void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims); union flightDynamicsTrims_u; void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse); void setAccelerationFilter(uint16_t initialAccLpfCutHz); - diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 10dbbc73cc..97254497a6 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -237,8 +237,8 @@ static void batteryUpdateVoltageState(void) } -static void batteryUpdateLVC(timeUs_t currentTimeUs) -{ +static void batteryUpdateLVC(timeUs_t currentTimeUs) +{ if (batteryConfig()->lvcPercentage < 100) { if (voltageState == BATTERY_CRITICAL && !lowVoltageCutoff.enabled) { lowVoltageCutoff.enabled = true; @@ -247,7 +247,7 @@ static void batteryUpdateLVC(timeUs_t currentTimeUs) } if (lowVoltageCutoff.enabled) { if (cmp32(currentTimeUs,lowVoltageCutoff.startTime) < LVC_AFFECT_TIME) { - lowVoltageCutoff.percentage = 100 - (cmp32(currentTimeUs,lowVoltageCutoff.startTime) * (100 - batteryConfig()->lvcPercentage) / LVC_AFFECT_TIME); + lowVoltageCutoff.percentage = 100 - (cmp32(currentTimeUs,lowVoltageCutoff.startTime) * (100 - batteryConfig()->lvcPercentage) / LVC_AFFECT_TIME); } else { lowVoltageCutoff.percentage = batteryConfig()->lvcPercentage; diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 044a5fb2ff..770c6b3759 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -44,7 +44,7 @@ typedef struct batteryConfig_s { uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V uint8_t vbatfullcellvoltage; // Cell voltage at which the battery is deemed to be "full" 0.1V units, default is 41 (4.1V) - + } batteryConfig_t; typedef struct lowVoltageCutoff_s { diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index a6486095b9..1d441a5c10 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -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)) - diff --git a/src/main/target/AIR32/target.mk b/src/main/target/AIR32/target.mk index dae15464f1..43b120d223 100644 --- a/src/main/target/AIR32/target.mk +++ b/src/main/target/AIR32/target.mk @@ -8,4 +8,3 @@ TARGET_SRC = \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c \ drivers/inverter.c - diff --git a/src/main/target/ALIENFLIGHTF1/AlienFlight.md b/src/main/target/ALIENFLIGHTF1/AlienFlight.md index cd700195a1..de204631b3 100644 --- a/src/main/target/ALIENFLIGHTF1/AlienFlight.md +++ b/src/main/target/ALIENFLIGHTF1/AlienFlight.md @@ -43,27 +43,27 @@ Here are the general hardware specifications for this boards: - 5V buck-boost power converter for FPV (some versions) - brushless versions are designed for 4S operation and also have an 5V power output - battery monitoring with an LED or buzzer output (for some variants only) -- current monitoring (F4/F7 V1.1 versions) +- current monitoring (F4/F7 V1.1 versions) - SDCard Reader for black box monitoring (F4/F7 V1.1 versions) - (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions) - hardware detection of brushed and brushless versions with individual defaults (*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator. - set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) + set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) set spektrum_sat_bind = 5 -(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de - +(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de + For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document. -Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. +Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs. (**) OpenSky receiver with telemetry is enabled by default if present on the board. -The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. +The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. ## Flashing the firmware diff --git a/src/main/target/ALIENFLIGHTF3/AlienFlight.md b/src/main/target/ALIENFLIGHTF3/AlienFlight.md index cd700195a1..de204631b3 100644 --- a/src/main/target/ALIENFLIGHTF3/AlienFlight.md +++ b/src/main/target/ALIENFLIGHTF3/AlienFlight.md @@ -43,27 +43,27 @@ Here are the general hardware specifications for this boards: - 5V buck-boost power converter for FPV (some versions) - brushless versions are designed for 4S operation and also have an 5V power output - battery monitoring with an LED or buzzer output (for some variants only) -- current monitoring (F4/F7 V1.1 versions) +- current monitoring (F4/F7 V1.1 versions) - SDCard Reader for black box monitoring (F4/F7 V1.1 versions) - (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions) - hardware detection of brushed and brushless versions with individual defaults (*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator. - set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) + set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) set spektrum_sat_bind = 5 -(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de - +(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de + For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document. -Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. +Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs. (**) OpenSky receiver with telemetry is enabled by default if present on the board. -The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. +The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. ## Flashing the firmware diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index a51264194d..eeb9581673 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -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 }; - diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index f6e7bbcaff..1e3a201ed7 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -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) ) - diff --git a/src/main/target/ALIENFLIGHTF3/target.mk b/src/main/target/ALIENFLIGHTF3/target.mk index ccf8916a8e..1b3c7c687d 100644 --- a/src/main/target/ALIENFLIGHTF3/target.mk +++ b/src/main/target/ALIENFLIGHTF3/target.mk @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/compass/compass_ak8963.c - diff --git a/src/main/target/ALIENFLIGHTF4/AlienFlight.md b/src/main/target/ALIENFLIGHTF4/AlienFlight.md index cd700195a1..de204631b3 100644 --- a/src/main/target/ALIENFLIGHTF4/AlienFlight.md +++ b/src/main/target/ALIENFLIGHTF4/AlienFlight.md @@ -43,27 +43,27 @@ Here are the general hardware specifications for this boards: - 5V buck-boost power converter for FPV (some versions) - brushless versions are designed for 4S operation and also have an 5V power output - battery monitoring with an LED or buzzer output (for some variants only) -- current monitoring (F4/F7 V1.1 versions) +- current monitoring (F4/F7 V1.1 versions) - SDCard Reader for black box monitoring (F4/F7 V1.1 versions) - (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions) - hardware detection of brushed and brushless versions with individual defaults (*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator. - set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) + set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) set spektrum_sat_bind = 5 -(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de - +(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de + For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document. -Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. +Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs. (**) OpenSky receiver with telemetry is enabled by default if present on the board. -The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. +The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. ## Flashing the firmware diff --git a/src/main/target/ALIENFLIGHTNGF7/AlienFlight.md b/src/main/target/ALIENFLIGHTNGF7/AlienFlight.md index cd700195a1..de204631b3 100644 --- a/src/main/target/ALIENFLIGHTNGF7/AlienFlight.md +++ b/src/main/target/ALIENFLIGHTNGF7/AlienFlight.md @@ -43,27 +43,27 @@ Here are the general hardware specifications for this boards: - 5V buck-boost power converter for FPV (some versions) - brushless versions are designed for 4S operation and also have an 5V power output - battery monitoring with an LED or buzzer output (for some variants only) -- current monitoring (F4/F7 V1.1 versions) +- current monitoring (F4/F7 V1.1 versions) - SDCard Reader for black box monitoring (F4/F7 V1.1 versions) - (**) integrated OpenSky (FrSky compatible) receiver with FrSky hub telemetry (F4/F7 V2 versions) - hardware detection of brushed and brushless versions with individual defaults (*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator. - set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) + set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) set spektrum_sat_bind = 5 -(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de - +(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de + For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document. -Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. +Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different. The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs. (**) OpenSky receiver with telemetry is enabled by default if present on the board. -The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. +The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator. ## Flashing the firmware diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 341d8d396f..79568a547c 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -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) ) - diff --git a/src/main/target/ALIENWHOOP/config.c b/src/main/target/ALIENWHOOP/config.c index 65b3a78d57..905b61c268 100644 --- a/src/main/target/ALIENWHOOP/config.c +++ b/src/main/target/ALIENWHOOP/config.c @@ -83,4 +83,3 @@ void targetConfiguration(void) compassConfigMutable()->mag_hardware = MAG_DEFAULT; } #endif - diff --git a/src/main/target/ALIENWHOOP/target.c b/src/main/target/ALIENWHOOP/target.c index ad775379f8..4fad7d26f3 100644 --- a/src/main/target/ALIENWHOOP/target.c +++ b/src/main/target/ALIENWHOOP/target.c @@ -52,4 +52,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), }; - diff --git a/src/main/target/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h index 2ce4b6f095..eebdb91099 100644 --- a/src/main/target/ALIENWHOOP/target.h +++ b/src/main/target/ALIENWHOOP/target.h @@ -228,4 +228,3 @@ */ #define USABLE_TIMER_CHANNEL_COUNT 5 #define USED_TIMERS ( TIM_N(3) | TIM_N(8) | TIM_N(5) ) - diff --git a/src/main/target/ANYFCF7/README.md b/src/main/target/ANYFCF7/README.md index bf8b4c7406..b73ac880c9 100644 --- a/src/main/target/ANYFCF7/README.md +++ b/src/main/target/ANYFCF7/README.md @@ -18,4 +18,3 @@ * support for CAN * SD card logging (SPI) * 3 AD channels, one with 10k/1k divider, two with 1k series resistor - diff --git a/src/main/target/ANYFCF7/target.mk b/src/main/target/ANYFCF7/target.mk index 9069b243f3..634ff0b825 100644 --- a/src/main/target/ANYFCF7/target.mk +++ b/src/main/target/ANYFCF7/target.mk @@ -8,4 +8,3 @@ TARGET_SRC = \ drivers/compass/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_hal.c - diff --git a/src/main/target/ANYFCM7/README.md b/src/main/target/ANYFCM7/README.md index 955d8b4746..a8c1038c0f 100644 --- a/src/main/target/ANYFCM7/README.md +++ b/src/main/target/ANYFCM7/README.md @@ -16,4 +16,3 @@ * external SPI (shared with U4/5) * 128Mb dataflash logging (SPI) * Voltage measurement, with 10k/1k divider - diff --git a/src/main/target/ANYFCM7/target.c b/src/main/target/ANYFCM7/target.c index 50f236fe01..e009620492 100644 --- a/src/main/target/ANYFCM7/target.c +++ b/src/main/target/ANYFCM7/target.c @@ -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 }; - diff --git a/src/main/target/BEEBRAIN_V2/target.c b/src/main/target/BEEBRAIN_V2/target.c index e66320510e..98813995b3 100755 --- a/src/main/target/BEEBRAIN_V2/target.c +++ b/src/main/target/BEEBRAIN_V2/target.c @@ -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 }; - diff --git a/src/main/target/BEEBRAIN_V2/target.h b/src/main/target/BEEBRAIN_V2/target.h index dda08be839..0cf5a10a59 100755 --- a/src/main/target/BEEBRAIN_V2/target.h +++ b/src/main/target/BEEBRAIN_V2/target.h @@ -117,4 +117,3 @@ #define USABLE_TIMER_CHANNEL_COUNT 4 #define USED_TIMERS ( TIM_N(1) | TIM_N(8) | TIM_N(15) ) - diff --git a/src/main/target/BEEBRAIN_V2/target.mk b/src/main/target/BEEBRAIN_V2/target.mk index 398cfa2e73..1f0a08a94d 100755 --- a/src/main/target/BEEBRAIN_V2/target.mk +++ b/src/main/target/BEEBRAIN_V2/target.mk @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/vtx_rtc6705_soft_spi.c \ drivers/max7456.c - diff --git a/src/main/target/BETAFLIGHTF3/readme.txt b/src/main/target/BETAFLIGHTF3/readme.txt index b6c5f279b0..cd339582bd 100755 --- a/src/main/target/BETAFLIGHTF3/readme.txt +++ b/src/main/target/BETAFLIGHTF3/readme.txt @@ -6,8 +6,8 @@ Board information: - CPU - STM32F303CCT6 - MPU-6000 -- SD Card Slot +- SD Card Slot - Build in 5V BEC + LC filter - board can be powered from main battery - Built in current meter, PDB -More info to come \ No newline at end of file +More info to come diff --git a/src/main/target/BLUEJAYF4/initialisation.c b/src/main/target/BLUEJAYF4/initialisation.c index 3f324c8e1a..d8c5863b45 100644 --- a/src/main/target/BLUEJAYF4/initialisation.c +++ b/src/main/target/BLUEJAYF4/initialisation.c @@ -74,4 +74,3 @@ void targetPreInit(void) IOHi(sdcardIo); } } - diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index 56951fc471..86ea41bebc 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -40,4 +40,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1) // S6_OUT }; - diff --git a/src/main/target/CC3D/target.mk b/src/main/target/CC3D/target.mk index 73a934e79a..aee2fd6271 100644 --- a/src/main/target/CC3D/target.mk +++ b/src/main/target/CC3D/target.mk @@ -8,4 +8,3 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c - diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c index 8ae562de61..7e06b70710 100644 --- a/src/main/target/CHEBUZZF3/target.c +++ b/src/main/target/CHEBUZZF3/target.c @@ -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 }; - diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 00726521b8..5b1c938535 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -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)) - diff --git a/src/main/target/CHEBUZZF3/target.mk b/src/main/target/CHEBUZZF3/target.mk index 471cb43b87..a21c116024 100644 --- a/src/main/target/CHEBUZZF3/target.mk +++ b/src/main/target/CHEBUZZF3/target.mk @@ -15,4 +15,3 @@ TARGET_SRC = \ drivers/barometer/barometer_ms5611.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_ak8975.c - diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c index f4f812bab9..df375914bc 100644 --- a/src/main/target/CJMCU/target.c +++ b/src/main/target/CJMCU/target.c @@ -41,4 +41,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0 ) // PWM14 - OUT6 }; - diff --git a/src/main/target/CJMCU/target.mk b/src/main/target/CJMCU/target.mk index d8e9e87676..072f7f22e0 100644 --- a/src/main/target/CJMCU/target.mk +++ b/src/main/target/CJMCU/target.mk @@ -9,4 +9,3 @@ TARGET_SRC = \ blackbox/blackbox_io.c \ telemetry/telemetry.c \ telemetry/ltm.c - diff --git a/src/main/target/CLRACINGF7/CL_RACINGF7.md b/src/main/target/CLRACINGF7/CL_RACINGF7.md index ac36ef7439..a7ed8267d5 100644 --- a/src/main/target/CLRACINGF7/CL_RACINGF7.md +++ b/src/main/target/CLRACINGF7/CL_RACINGF7.md @@ -9,5 +9,5 @@ Blackbox: SD Card PPM/UART NOT Shared: YES Battery Voltage Sensor: 10:1 Current sensor: 0.5 mOhm, 250 Current scale in the setting -Integrated Voltage Regulator: 3 A 5v +Integrated Voltage Regulator: 3 A 5v 120A Current sensing PDB and 150A burst current for 10S on the current sensing Resistor diff --git a/src/main/target/COLIBRI/target.mk b/src/main/target/COLIBRI/target.mk index 9f7a73bd80..af8364ed0e 100644 --- a/src/main/target/COLIBRI/target.mk +++ b/src/main/target/COLIBRI/target.mk @@ -6,4 +6,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c - diff --git a/src/main/target/COLIBRI_RACE/bus_bst.h b/src/main/target/COLIBRI_RACE/bus_bst.h index d2ead1e544..1594cca5cd 100644 --- a/src/main/target/COLIBRI_RACE/bus_bst.h +++ b/src/main/target/COLIBRI_RACE/bus_bst.h @@ -44,4 +44,3 @@ bool bstSlaveWrite(uint8_t* data); void bstMasterWriteLoop(void); void crc8Cal(uint8_t data_in); - diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 4314cf9fad..84ec4dadce 100644 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -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)) - diff --git a/src/main/target/ELLE0/target.c b/src/main/target/ELLE0/target.c index b350ddf36b..5943258fef 100644 --- a/src/main/target/ELLE0/target.c +++ b/src/main/target/ELLE0/target.c @@ -47,5 +47,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // I2C //UART3 RX: DMA1_ST1 //UART3 TX: DMA1_ST3 - - diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index 35c750cad2..65260ba376 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -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 }; - diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index d2b9b27b90..26472bd845 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -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)) - diff --git a/src/main/target/F4BY/target.mk b/src/main/target/F4BY/target.mk index afe00b8138..ec2205cc53 100644 --- a/src/main/target/F4BY/target.mk +++ b/src/main/target/F4BY/target.mk @@ -5,4 +5,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c - diff --git a/src/main/target/FF_FORTINIF4/target.mk b/src/main/target/FF_FORTINIF4/target.mk index 13717c509b..52343e2fb8 100644 --- a/src/main/target/FF_FORTINIF4/target.mk +++ b/src/main/target/FF_FORTINIF4/target.mk @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_spi_icm20689.c \ drivers/max7456.c - \ No newline at end of file diff --git a/src/main/target/FF_PIKOBLX/target.c b/src/main/target/FF_PIKOBLX/target.c index 8582b58682..b90760b0de 100644 --- a/src/main/target/FF_PIKOBLX/target.c +++ b/src/main/target/FF_PIKOBLX/target.c @@ -47,4 +47,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1 ), // TRANSPONDER - PA8 #endif }; - diff --git a/src/main/target/FURYF4/target.c b/src/main/target/FURYF4/target.c index c2bcb4bfb9..04cac613d5 100644 --- a/src/main/target/FURYF4/target.c +++ b/src/main/target/FURYF4/target.c @@ -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 }; - diff --git a/src/main/target/FURYF7/README.md b/src/main/target/FURYF7/README.md index 9b6255a618..df66fc8a5d 100644 --- a/src/main/target/FURYF7/README.md +++ b/src/main/target/FURYF7/README.md @@ -10,9 +10,9 @@ * SD card (Not currently working, Fatal Error) * 16MB Flash (Not currently working, no chip detected) * ADC (RSSI, CURR, VBAT) -* I2C +* I2C * LED Strip * Built in 5v 2A Regulator * Spek Sat Connector * SWD Port -* Beeper output \ No newline at end of file +* Beeper output diff --git a/src/main/target/IMPULSERCF3/target.mk b/src/main/target/IMPULSERCF3/target.mk index 9a1ca5dc5b..53b083d225 100644 --- a/src/main/target/IMPULSERCF3/target.mk +++ b/src/main/target/IMPULSERCF3/target.mk @@ -5,4 +5,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/flash_m25p16.c - diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index 67acfa0f0a..c1005ca58b 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -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 }; - diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 703b9a0f25..0112c6477e 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -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)) - diff --git a/src/main/target/IRCFUSIONF3/target.mk b/src/main/target/IRCFUSIONF3/target.mk index fe03501b51..94df931d53 100644 --- a/src/main/target/IRCFUSIONF3/target.mk +++ b/src/main/target/IRCFUSIONF3/target.mk @@ -6,4 +6,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu6050.c \ drivers/barometer/barometer_bmp085.c - diff --git a/src/main/target/ISHAPEDF3/target.c b/src/main/target/ISHAPEDF3/target.c index 4fc2745605..a5d417fb32 100644 --- a/src/main/target/ISHAPEDF3/target.c +++ b/src/main/target/ISHAPEDF3/target.c @@ -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 }; - diff --git a/src/main/target/ISHAPEDF3/target.h b/src/main/target/ISHAPEDF3/target.h index 6813d2094e..10549e06aa 100644 --- a/src/main/target/ISHAPEDF3/target.h +++ b/src/main/target/ISHAPEDF3/target.h @@ -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) ) - - diff --git a/src/main/target/KAKUTEF4/target.c b/src/main/target/KAKUTEF4/target.c index e47da1449c..d61a95fae8 100644 --- a/src/main/target/KAKUTEF4/target.c +++ b/src/main/target/KAKUTEF4/target.c @@ -32,4 +32,4 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5_OUT - DMA1_ST2 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S6_OUT - DMA2_ST4 DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0), // LED_STRIP - DMA1_ST4 -}; \ No newline at end of file +}; diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index 7e2e3dc217..8c22321a1b 100644 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -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)) - diff --git a/src/main/target/KIWIF4/README.md b/src/main/target/KIWIF4/README.md index cdc79193b3..7adfc67fd6 100644 --- a/src/main/target/KIWIF4/README.md +++ b/src/main/target/KIWIF4/README.md @@ -13,4 +13,3 @@ Available at: flyinglemon.eu - Other connectors: RSSI, Current sensor, LED strip, Buzzer, Video IN/Out + LC filter - dedicated PDB with current sensor - Size: 36mm x 36mm - diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h index b2f8fee45d..4f527d3652 100644 --- a/src/main/target/KIWIF4/target.h +++ b/src/main/target/KIWIF4/target.h @@ -191,4 +191,3 @@ #define CMS #define USE_MSP_DISPLAYPORT - diff --git a/src/main/target/KIWIF4/target.mk b/src/main/target/KIWIF4/target.mk index a6eb0761e5..1cb2eec9a1 100644 --- a/src/main/target/KIWIF4/target.mk +++ b/src/main/target/KIWIF4/target.mk @@ -5,4 +5,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/max7456.c \ io/osd.c - diff --git a/src/main/target/KROOZX/initialisation.c b/src/main/target/KROOZX/initialisation.c index fa8310910a..069e1e3616 100755 --- a/src/main/target/KROOZX/initialisation.c +++ b/src/main/target/KROOZX/initialisation.c @@ -28,4 +28,3 @@ void targetPreInit(void) IOConfigGPIO(osdChSwitch, IOCFG_OUT_PP); IOLo(osdChSwitch); } - diff --git a/src/main/target/KROOZX/target.mk b/src/main/target/KROOZX/target.mk index 33f2d3eeaf..a0bf89c18e 100755 --- a/src/main/target/KROOZX/target.mk +++ b/src/main/target/KROOZX/target.mk @@ -6,4 +6,4 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c \ - drivers/max7456.c \ No newline at end of file + drivers/max7456.c diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index 34b7072b16..4ae960732b 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -42,4 +42,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM16, CH1, PA6, TIM_USE_LED, 1), }; - diff --git a/src/main/target/LUX_RACE/target.mk b/src/main/target/LUX_RACE/target.mk index ba6f65ede8..a85188a428 100644 --- a/src/main/target/LUX_RACE/target.mk +++ b/src/main/target/LUX_RACE/target.mk @@ -6,4 +6,4 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ No newline at end of file + drivers/accgyro/accgyro_spi_mpu6000.c diff --git a/src/main/target/MATEKF405/target.c b/src/main/target/MATEKF405/target.c index 9e6249a0b3..f23af357ee 100644 --- a/src/main/target/MATEKF405/target.c +++ b/src/main/target/MATEKF405/target.c @@ -37,4 +37,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED DMA1_ST0 }; - diff --git a/src/main/target/MATEKF405/target.mk b/src/main/target/MATEKF405/target.mk index 4ec7277fea..8aec080d35 100644 --- a/src/main/target/MATEKF405/target.mk +++ b/src/main/target/MATEKF405/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6500.c \ diff --git a/src/main/target/MATEKF722/target.c b/src/main/target/MATEKF722/target.c index 71fd80c51f..a1f32868b3 100644 --- a/src/main/target/MATEKF722/target.c +++ b/src/main/target/MATEKF722/target.c @@ -37,4 +37,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED STRIP DMA1_ST5 }; - diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk index 7ca6032c90..0d2bdb5751 100644 --- a/src/main/target/MATEKF722/target.mk +++ b/src/main/target/MATEKF722/target.mk @@ -1,6 +1,6 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro/accgyro_spi_icm20689.c \ - drivers/max7456.c \ No newline at end of file + drivers/max7456.c diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c index 414404fbbe..9c8abc9b97 100644 --- a/src/main/target/MOTOLAB/target.c +++ b/src/main/target/MOTOLAB/target.c @@ -36,4 +36,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0 ), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0 ), // LED - PB8 - *TIM16_CH1, TIM4_CH3, TIM8_CH2 }; - diff --git a/src/main/target/MOTOLAB/target.mk b/src/main/target/MOTOLAB/target.mk index 8862ca16fd..96b7254d3b 100644 --- a/src/main/target/MOTOLAB/target.mk +++ b/src/main/target/MOTOLAB/target.mk @@ -6,4 +6,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6050.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/flash_m25p16.c - diff --git a/src/main/target/MOTOLABF4/config.c b/src/main/target/MOTOLABF4/config.c index e70c4c9d31..94c8bf946d 100644 --- a/src/main/target/MOTOLABF4/config.c +++ b/src/main/target/MOTOLABF4/config.c @@ -31,4 +31,3 @@ void targetConfiguration(void) telemetryConfigMutable()->halfDuplex = 0; } #endif - diff --git a/src/main/target/MOTOLABF4/target.mk b/src/main/target/MOTOLABF4/target.mk index a65c46ace8..8f348d0afb 100644 --- a/src/main/target/MOTOLABF4/target.mk +++ b/src/main/target/MOTOLABF4/target.mk @@ -11,4 +11,3 @@ TARGET_SRC = \ drivers/max7456.c \ drivers/vtx_rtc6705_soft_spi.c endif - diff --git a/src/main/target/MULTIFLITEPICO/MULTIFLITEPICO.md b/src/main/target/MULTIFLITEPICO/MULTIFLITEPICO.md index dacc0d7ba3..6d0f4b88b0 100755 --- a/src/main/target/MULTIFLITEPICO/MULTIFLITEPICO.md +++ b/src/main/target/MULTIFLITEPICO/MULTIFLITEPICO.md @@ -33,12 +33,12 @@ The features of the FC are detailed below: (*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the BetaFlight Configurator. - set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) + set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit) set spektrum_sat_bind = 5 - + For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document. -Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different. +Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different. The pin layout for the MULTIFLITEPICO is very similar to SPRACINGF3. diff --git a/src/main/target/MULTIFLITEPICO/target.mk b/src/main/target/MULTIFLITEPICO/target.mk index 0fbfe6bd57..9a79fa4710 100755 --- a/src/main/target/MULTIFLITEPICO/target.mk +++ b/src/main/target/MULTIFLITEPICO/target.mk @@ -1,5 +1,5 @@ F3_TARGETS += $(TARGET) -FEATURES = +FEATURES = TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ @@ -9,4 +9,3 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c - diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index 75c0b27766..520a7b7152 100755 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -118,4 +118,3 @@ ioTag_t selectMPUIntExtiConfigByHardwareRevision(void) } #endif } - diff --git a/src/main/target/NERO/NERO.md b/src/main/target/NERO/NERO.md index 3016d558df..1a256465ae 100644 --- a/src/main/target/NERO/NERO.md +++ b/src/main/target/NERO/NERO.md @@ -2,4 +2,4 @@ Placeholder for NERO (an STM32F722RE target) - in both 30.5x30.5 and 20x20 (mini) formats. -Samples are being made now, with production run expected once STM32 release the 722RE in production quantities. \ No newline at end of file +Samples are being made now, with production run expected once STM32 release the 722RE in production quantities. diff --git a/src/main/target/NUCLEOF722/target.c b/src/main/target/NUCLEOF722/target.c index 3c02108130..cdaf0273f1 100644 --- a/src/main/target/NUCLEOF722/target.c +++ b/src/main/target/NUCLEOF722/target.c @@ -39,4 +39,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), }; - diff --git a/src/main/target/OMNIBUSF4/DYSF4PRO.mk b/src/main/target/OMNIBUSF4/DYSF4PRO.mk index 290de85f12..4e7c3736ef 100644 --- a/src/main/target/OMNIBUSF4/DYSF4PRO.mk +++ b/src/main/target/OMNIBUSF4/DYSF4PRO.mk @@ -1 +1 @@ -#DYSF4PRO \ No newline at end of file +#DYSF4PRO diff --git a/src/main/target/OMNIBUSF4/LUXF4OSD.mk b/src/main/target/OMNIBUSF4/LUXF4OSD.mk index 848e3afad2..bd8745e892 100644 --- a/src/main/target/OMNIBUSF4/LUXF4OSD.mk +++ b/src/main/target/OMNIBUSF4/LUXF4OSD.mk @@ -1 +1 @@ -#LUXF4OSD.mk file \ No newline at end of file +#LUXF4OSD.mk file diff --git a/src/main/target/OMNIBUSF7/target.mk b/src/main/target/OMNIBUSF7/target.mk index 1f41520c50..07f3186be1 100644 --- a/src/main/target/OMNIBUSF7/target.mk +++ b/src/main/target/OMNIBUSF7/target.mk @@ -11,4 +11,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_hal.c \ drivers/max7456.c - diff --git a/src/main/target/RACEBASE/hardware_revision.c b/src/main/target/RACEBASE/hardware_revision.c index fc56c4e87e..0d626356e7 100755 --- a/src/main/target/RACEBASE/hardware_revision.c +++ b/src/main/target/RACEBASE/hardware_revision.c @@ -59,4 +59,3 @@ void updateHardwareRevision(void) { } - diff --git a/src/main/target/RACEBASE/readme.txt b/src/main/target/RACEBASE/readme.txt index a2507bcd3e..233b99c33f 100755 --- a/src/main/target/RACEBASE/readme.txt +++ b/src/main/target/RACEBASE/readme.txt @@ -21,4 +21,4 @@ Photo: https://cdn.shoplo.com/0639/products/th1024/aaaw/838-rr_flight_controller_rotoracer_fc_rotoracer_racebase.jpg Port description: -https://cdn.shoplo.com/0639/products/th1024/aaaw/844-racebase-render-en.png \ No newline at end of file +https://cdn.shoplo.com/0639/products/th1024/aaaw/844-racebase-render-en.png diff --git a/src/main/target/RACEBASE/target.h b/src/main/target/RACEBASE/target.h index 6bdaf99999..a8e8bbd78d 100644 --- a/src/main/target/RACEBASE/target.h +++ b/src/main/target/RACEBASE/target.h @@ -120,6 +120,3 @@ #define USABLE_TIMER_CHANNEL_COUNT 6 #define USED_TIMERS (TIM_N(2) | TIM_N(3)| TIM_N(4) | TIM_N(8) | TIM_N(17)) - - - diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index b49b2adda3..4ab37ee22d 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -277,4 +277,3 @@ #define USABLE_TIMER_CHANNEL_COUNT 12 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) #endif - diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index f2a21cc716..ca8711f432 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -89,4 +89,3 @@ #define USABLE_TIMER_CHANNEL_COUNT 12 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) ) - diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h index 60a6b1567b..ee3cc772b3 100644 --- a/src/main/target/RG_SSD_F3/target.h +++ b/src/main/target/RG_SSD_F3/target.h @@ -153,4 +153,3 @@ #define USED_TIMERS (TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17)) #define USABLE_TIMER_CHANNEL_COUNT 9 - diff --git a/src/main/target/SINGULARITY/target.c b/src/main/target/SINGULARITY/target.c index c4986499ed..763d5d7537 100644 --- a/src/main/target/SINGULARITY/target.c +++ b/src/main/target/SINGULARITY/target.c @@ -36,4 +36,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, 1), // SOFTSERIAL1 TX DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 1), // LED_STRIP }; - diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c index 42e4a5390e..ee63dcceca 100644 --- a/src/main/target/SIRINFPV/target.c +++ b/src/main/target/SIRINFPV/target.c @@ -33,5 +33,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_ENABLED), // PWM5 - PB0 - *TIM3_CH3 DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED),// PWM6 - PB1 - *TIM3_CH4 }; - - diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 5bb5fc6b9c..dfa05e6a14 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -160,4 +160,3 @@ #define USABLE_TIMER_CHANNEL_COUNT 7 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(17)) - diff --git a/src/main/target/SITL/README.md b/src/main/target/SITL/README.md index 9eb7de0842..55234bc09d 100644 --- a/src/main/target/SITL/README.md +++ b/src/main/target/SITL/README.md @@ -45,5 +45,3 @@ UARTx will bind on `tcp://127.0.0.1:576x` when port been open. `eeprom.bin`, size 8192 Byte, is for config saving. size can be changed in `src/main/target/SITL/parameter_group.ld` >> `__FLASH_CONFIG_Size` - - diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 56ccc1ac6b..0ab64e0821 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -249,4 +249,3 @@ uint64_t micros64(); uint64_t millis64(); int lockMainPID(void); - diff --git a/src/main/target/SITL/target.mk b/src/main/target/SITL/target.mk index 3b2e26b0fd..801acaf0a2 100644 --- a/src/main/target/SITL/target.mk +++ b/src/main/target/SITL/target.mk @@ -6,4 +6,3 @@ TARGET_SRC = \ drivers/barometer/barometer_fake.c \ drivers/compass/compass_fake.c \ drivers/serial_tcp.c - diff --git a/src/main/target/SITL/udplink.c b/src/main/target/SITL/udplink.c index 2a4a4deafe..312844f25f 100644 --- a/src/main/target/SITL/udplink.c +++ b/src/main/target/SITL/udplink.c @@ -65,4 +65,3 @@ int udpRecv(udpLink_t* link, void* data, size_t size, uint32_t timeout_ms) { ret = recvfrom(link->fd, data, size, 0, (struct sockaddr *)&link->recv, &len); return ret; } - diff --git a/src/main/target/SITL/udplink.h b/src/main/target/SITL/udplink.h index c51417cafe..0c40c5b67c 100644 --- a/src/main/target/SITL/udplink.h +++ b/src/main/target/SITL/udplink.h @@ -37,4 +37,3 @@ int udpSend(udpLink_t* link, const void* data, size_t size); #endif #endif - diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c index dd1a54c45e..787a524594 100644 --- a/src/main/target/SPARKY/target.c +++ b/src/main/target/SPARKY/target.c @@ -39,4 +39,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0), // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0) // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 }; - diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 6267d3f371..4de37b1d76 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -104,4 +104,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)) - diff --git a/src/main/target/SPARKY/target.mk b/src/main/target/SPARKY/target.mk index 2911edc25d..b0c536ce9f 100644 --- a/src/main/target/SPARKY/target.mk +++ b/src/main/target/SPARKY/target.mk @@ -1,5 +1,5 @@ F3_TARGETS += $(TARGET) -FEATURES = VCP +FEATURES = VCP TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/barometer/barometer_ms5611.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_ak8975.c - diff --git a/src/main/target/SPARKY2/target.c b/src/main/target/SPARKY2/target.c index 1bf8f23511..d355ee913f 100644 --- a/src/main/target/SPARKY2/target.c +++ b/src/main/target/SPARKY2/target.c @@ -37,4 +37,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 1, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3 DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0 ), // S6_OUT }; - diff --git a/src/main/target/SPARKY2/target.mk b/src/main/target/SPARKY2/target.mk index 6b658e85e9..a07c15d242 100644 --- a/src/main/target/SPARKY2/target.mk +++ b/src/main/target/SPARKY2/target.mk @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_hmc5883l.c - diff --git a/src/main/target/SPRACINGF3MINI/target.mk b/src/main/target/SPRACINGF3MINI/target.mk index 992821b714..075b712d52 100644 --- a/src/main/target/SPRACINGF3MINI/target.mk +++ b/src/main/target/SPRACINGF3MINI/target.mk @@ -1,5 +1,5 @@ F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD +FEATURES = VCP SDCARD TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ @@ -8,7 +8,7 @@ TARGET_SRC = \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ - drivers/flash_m25p16.c + drivers/flash_m25p16.c ifeq ($(TARGET), TINYBEEF3) TARGET_SRC += \ diff --git a/src/main/target/SPRACINGF3NEO/target.c b/src/main/target/SPRACINGF3NEO/target.c index 206423d8c8..0191de2c26 100755 --- a/src/main/target/SPRACINGF3NEO/target.c +++ b/src/main/target/SPRACINGF3NEO/target.c @@ -58,4 +58,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0 ), }; - diff --git a/src/main/target/SPRACINGF3OSD/target.c b/src/main/target/SPRACINGF3OSD/target.c index ebd888f4bb..f08dcb2a63 100644 --- a/src/main/target/SPRACINGF3OSD/target.c +++ b/src/main/target/SPRACINGF3OSD/target.c @@ -33,4 +33,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 0 ), }; - diff --git a/src/main/target/SPRACINGF4EVO/target.mk b/src/main/target/SPRACINGF4EVO/target.mk index 7ab78d9b70..9ae5387862 100644 --- a/src/main/target/SPRACINGF4EVO/target.mk +++ b/src/main/target/SPRACINGF4EVO/target.mk @@ -10,5 +10,3 @@ TARGET_SRC = \ drivers/compass/compass_hmc5883l.c \ drivers/max7456.c \ drivers/vtx_rtc6705.c - - diff --git a/src/main/target/SPRACINGF4NEO/config.c b/src/main/target/SPRACINGF4NEO/config.c index f7261352d1..d64bde9ed1 100644 --- a/src/main/target/SPRACINGF4NEO/config.c +++ b/src/main/target/SPRACINGF4NEO/config.c @@ -34,4 +34,3 @@ void targetConfiguration(void) telemetryConfigMutable()->halfDuplex = false; } #endif - diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h index e1fc7fa6a4..b16a7ad680 100644 --- a/src/main/target/SPRACINGF4NEO/target.h +++ b/src/main/target/SPRACINGF4NEO/target.h @@ -229,4 +229,3 @@ #define USABLE_TIMER_CHANNEL_COUNT 14 // 4xPWM, 6xESC, 2xESC via UART3 RX/TX, 1xLED Strip, 1xIR. #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9)) - diff --git a/src/main/target/SPRACINGF4NEO/target.mk b/src/main/target/SPRACINGF4NEO/target.mk index 9fc84c6650..f98d9afc31 100644 --- a/src/main/target/SPRACINGF4NEO/target.mk +++ b/src/main/target/SPRACINGF4NEO/target.mk @@ -13,5 +13,3 @@ TARGET_SRC = \ drivers/vtx_rtc6705.c \ io/osd.c \ io/transponder_ir.c \ - - diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index 60e6e31e19..0d55005386 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -42,4 +42,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM2, CH3, PA2, 0, 0) }; - diff --git a/src/main/target/TINYFISH/target.c b/src/main/target/TINYFISH/target.c index 15a83024b3..123501ab38 100644 --- a/src/main/target/TINYFISH/target.c +++ b/src/main/target/TINYFISH/target.c @@ -32,4 +32,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, TIMER_OUTPUT_ENABLED) //DMA1_CH2 - LED }; - diff --git a/src/main/target/TINYFISH/target.mk b/src/main/target/TINYFISH/target.mk index 0d256e76a8..bb86079a7d 100644 --- a/src/main/target/TINYFISH/target.mk +++ b/src/main/target/TINYFISH/target.mk @@ -4,4 +4,4 @@ FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/flash_m25p16.c \ - drivers/accgyro/accgyro_spi_mpu6000.c + drivers/accgyro/accgyro_spi_mpu6000.c diff --git a/src/main/target/VRRACE/target.c b/src/main/target/VRRACE/target.c index 88754414f8..a4a7da0ea4 100644 --- a/src/main/target/VRRACE/target.c +++ b/src/main/target/VRRACE/target.c @@ -37,4 +37,4 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 1, 0), // S4_OUT DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // S5_OUT DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // S6_OUT -}; \ No newline at end of file +}; diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk index 4ac13fe185..2ae3a4b8cb 100644 --- a/src/main/target/X_RACERSPI/target.mk +++ b/src/main/target/X_RACERSPI/target.mk @@ -8,4 +8,3 @@ TARGET_SRC = \ drivers/compass/compass_hmc5883l.c \ drivers/display_ug2864hsweg01.h \ drivers/flash_m25p16.c - diff --git a/src/main/target/YUPIF4/target.c b/src/main/target/YUPIF4/target.c index 77cf5aafc1..1bd5f4a6a6 100644 --- a/src/main/target/YUPIF4/target.c +++ b/src/main/target/YUPIF4/target.c @@ -36,4 +36,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, TIMER_OUTPUT_ENABLED, 0 ), // BEEPER PWM DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, TIMER_OUTPUT_ENABLED, 0 ), // BEEPER PWM OPT }; - diff --git a/src/main/target/YUPIF4/target.mk b/src/main/target/YUPIF4/target.mk index 4efc03586c..8047b59f40 100644 --- a/src/main/target/YUPIF4/target.mk +++ b/src/main/target/YUPIF4/target.mk @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/accgyro/accgyro_spi_icm20689.c\ drivers/max7456.c \ io/osd.c - diff --git a/src/main/telemetry/crsf.h b/src/main/telemetry/crsf.h index 1b5fa6b95b..980467f517 100644 --- a/src/main/telemetry/crsf.h +++ b/src/main/telemetry/crsf.h @@ -32,4 +32,3 @@ bool checkCrsfTelemetryState(void); void handleCrsfTelemetry(timeUs_t currentTimeUs); int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType); - diff --git a/src/main/telemetry/hott.h b/src/main/telemetry/hott.h index 660c4266ab..64c34a953f 100644 --- a/src/main/telemetry/hott.h +++ b/src/main/telemetry/hott.h @@ -497,4 +497,3 @@ void freeHoTTTelemetryPort(void); uint32_t getHoTTTelemetryProviderBaudRate(void); void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage); - diff --git a/src/main/telemetry/ibus_shared.h b/src/main/telemetry/ibus_shared.h index 89a62a86ee..9c25aaff4f 100644 --- a/src/main/telemetry/ibus_shared.h +++ b/src/main/telemetry/ibus_shared.h @@ -39,6 +39,3 @@ void initSharedIbusTelemetry(serialPort_t * port); bool isChecksumOkIa6b(const uint8_t *ibusPacket, const uint8_t length); - - - diff --git a/src/main/telemetry/ltm.h b/src/main/telemetry/ltm.h index 892d0efdd8..60f2af16d2 100644 --- a/src/main/telemetry/ltm.h +++ b/src/main/telemetry/ltm.h @@ -25,4 +25,3 @@ void checkLtmTelemetryState(void); void freeLtmTelemetryPort(void); void configureLtmTelemetryPort(void); - diff --git a/src/main/vcp/usb_prop.c b/src/main/vcp/usb_prop.c index be822f155a..83f996357e 100644 --- a/src/main/vcp/usb_prop.c +++ b/src/main/vcp/usb_prop.c @@ -375,4 +375,3 @@ uint32_t Virtual_Com_Port_GetBaudRate(void) } /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcp/usb_prop.h b/src/main/vcp/usb_prop.h index f8e1d20249..12e42a6452 100644 --- a/src/main/vcp/usb_prop.h +++ b/src/main/vcp/usb_prop.h @@ -83,4 +83,3 @@ uint32_t Virtual_Com_Port_GetBaudRate(void); #endif /* __usb_prop_H */ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c index fa03247838..ef34a0932b 100644 --- a/src/main/vcp_hal/usbd_desc.c +++ b/src/main/vcp_hal/usbd_desc.c @@ -303,4 +303,3 @@ static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len) } } /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcpf4/usb_conf.h b/src/main/vcpf4/usb_conf.h index 214888654c..90d643d410 100644 --- a/src/main/vcpf4/usb_conf.h +++ b/src/main/vcpf4/usb_conf.h @@ -286,4 +286,3 @@ * @} */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcpf4/usbd_cdc_vcp.h b/src/main/vcpf4/usbd_cdc_vcp.h index 7ef4535883..0fd0761eb5 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.h +++ b/src/main/vcpf4/usbd_cdc_vcp.h @@ -71,4 +71,3 @@ typedef struct #endif /* __USBD_CDC_VCP_H */ - diff --git a/src/main/vcpf4/usbd_conf.h b/src/main/vcpf4/usbd_conf.h index 1978c8d957..f2b3e63340 100644 --- a/src/main/vcpf4/usbd_conf.h +++ b/src/main/vcpf4/usbd_conf.h @@ -97,4 +97,3 @@ #endif //__USBD_CONF__H__ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c index cdba125ba4..768e2928d9 100644 --- a/src/main/vcpf4/usbd_desc.c +++ b/src/main/vcpf4/usbd_desc.c @@ -314,4 +314,3 @@ uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length) */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcpf4/usbd_usr.c b/src/main/vcpf4/usbd_usr.c index 24c5f17c20..b5da4143d4 100644 --- a/src/main/vcpf4/usbd_usr.c +++ b/src/main/vcpf4/usbd_usr.c @@ -122,5 +122,3 @@ void USBD_USR_DeviceResumed(void) { /* Users can do their application actions here for the USB-Reset */ } - - diff --git a/src/test/Makefile b/src/test/Makefile index 835fadc1bc..b9a960ef0d 100644 --- a/src/test/Makefile +++ b/src/test/Makefile @@ -82,7 +82,7 @@ cli_unittest_SRC := \ $(USER_DIR)/fc/cli.c \ $(USER_DIR)/config/feature.c \ $(USER_DIR)/config/parameter_group.c \ - $(USER_DIR)/common/typeconversion.c + $(USER_DIR)/common/typeconversion.c cli_unittest_DEFINES := \ USE_CLI \ @@ -446,4 +446,3 @@ endef #apply the canned recipe above to all tests $(eval $(foreach test,$(TESTS),$(call test-specific-stuff,$(test)))) - diff --git a/src/test/unit/alignsensor_unittest.cc b/src/test/unit/alignsensor_unittest.cc index 4fcaaecef0..4037c760d4 100644 --- a/src/test/unit/alignsensor_unittest.cc +++ b/src/test/unit/alignsensor_unittest.cc @@ -32,9 +32,9 @@ extern "C" { * This test file contains an independent method of rotating a vector. * The output of alignSensor() is compared to the output of the test * rotation method. - * + * * For each alignment condition (CW0, CW90, etc) the source vector under - * test is set to a unit vector along each axis (x-axis, y-axis, z-axis) + * test is set to a unit vector along each axis (x-axis, y-axis, z-axis) * plus one additional random vector is tested. */ @@ -50,7 +50,7 @@ static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out) tmp[i] += mat[j][i] * vec[j]; } } - + out[0]=tmp[0]; out[1]=tmp[1]; out[2]=tmp[2]; @@ -105,7 +105,7 @@ static void testCW(sensor_align_e rotation, int32_t angle) src[X] = 1; src[Y] = 0; src[Z] = 0; - + int32_t matrix[3][3]; initZAxisRotation(matrix, angle); rotateVector(matrix, src, test); @@ -162,7 +162,7 @@ static void testCWFlip(sensor_align_e rotation, int32_t angle) src[X] = 1; src[Y] = 0; src[Z] = 0; - + int32_t matrix[3][3]; initYAxisRotation(matrix, 180); rotateVector(matrix, src, test); @@ -223,7 +223,7 @@ static void testCWFlip(sensor_align_e rotation, int32_t angle) EXPECT_EQ(test[Y], src[Y]) << "Random alignment does not match in Y-Axis. " << test[Y] << " " << src[Y]; EXPECT_EQ(test[Z], src[Z]) << "Random alignment does not match in Z-Axis. " << test[Z] << " " << src[Z]; } - + TEST(AlignSensorTest, ClockwiseZeroDegrees) { @@ -265,4 +265,3 @@ TEST(AlignSensorTest, ClockwiseTwoSeventyDegreesFlip) { testCWFlip(CW270_DEG_FLIP, 270); } - diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc index 03fc00a44a..68a1bbb5c6 100644 --- a/src/test/unit/cli_unittest.cc +++ b/src/test/unit/cli_unittest.cc @@ -60,7 +60,7 @@ extern "C" { }; const uint16_t valueTableEntryCount = ARRAYLEN(valueTable); const lookupTableEntry_t lookupTables[] = {}; - + PG_REGISTER(osdConfig_t, osdConfig, PG_OSD_CONFIG, 0); PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0); @@ -81,7 +81,7 @@ extern "C" { PG_REGISTER_ARRAY(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs, PG_RX_FAILSAFE_CHANNEL_CONFIG, 0); PG_REGISTER(pidConfig_t, pidConfig, PG_PID_CONFIG, 0); - PG_REGISTER_WITH_RESET_FN(int8_t, unitTestData, PG_RESERVED_FOR_TESTING_1, 0); + PG_REGISTER_WITH_RESET_FN(int8_t, unitTestData, PG_RESERVED_FOR_TESTING_1, 0); } #include "unittest_macros.h" diff --git a/src/test/unit/gps_conversion_unittest.cc b/src/test/unit/gps_conversion_unittest.cc index 826594baad..78e3e51ac7 100644 --- a/src/test/unit/gps_conversion_unittest.cc +++ b/src/test/unit/gps_conversion_unittest.cc @@ -72,4 +72,3 @@ TEST(GpsConversionTest, GPSCoordToDegrees_NMEA_Values) EXPECT_EQ(result, expectation->degrees); } } - diff --git a/src/test/unit/parameter_groups_unittest.cc b/src/test/unit/parameter_groups_unittest.cc index 4ef93af25a..211109fa3d 100644 --- a/src/test/unit/parameter_groups_unittest.cc +++ b/src/test/unit/parameter_groups_unittest.cc @@ -87,4 +87,3 @@ TEST(ParameterGroupsfTest, Test_pgFind) extern "C" { } - diff --git a/src/test/unit/rcsplit_unittest.cc b/src/test/unit/rcsplit_unittest.cc index 8f0f6e2b55..fafa274013 100644 --- a/src/test/unit/rcsplit_unittest.cc +++ b/src/test/unit/rcsplit_unittest.cc @@ -34,7 +34,7 @@ extern "C" { #include "fc/rc_controls.h" #include "fc/rc_modes.h" - + #include "io/beeper.h" #include "io/serial.h" @@ -118,13 +118,13 @@ TEST(RCSplitTest, TestRecvWhoAreYouResponse) unitTestResetRCSplit(); testData.isRunCamSplitOpenPortSupported = true; testData.isRunCamSplitPortConfigurated = true; - + bool result = rcSplitInit(); EXPECT_EQ(true, result); - // here will generate a number in [6-255], it's make the serialRxBytesWaiting() and serialRead() run at least 5 times, + // here will generate a number in [6-255], it's make the serialRxBytesWaiting() and serialRead() run at least 5 times, // so the "who are you response" will full received, and cause the state change to RCSPLIT_STATE_IS_READY; - int8_t randNum = rand() % 127 + 6; + int8_t randNum = rand() % 127 + 6; testData.maxTimesOfRespDataAvailable = randNum; rcSplitProcess((timeUs_t)0); @@ -138,7 +138,7 @@ TEST(RCSplitTest, TestWifiModeChangeWithDeviceUnready) testData.isRunCamSplitOpenPortSupported = true; testData.isRunCamSplitPortConfigurated = true; testData.maxTimesOfRespDataAvailable = 0; - + bool result = rcSplitInit(); EXPECT_EQ(true, result); @@ -187,7 +187,7 @@ TEST(RCSplitTest, TestWifiModeChangeWithDeviceReady) testData.isRunCamSplitOpenPortSupported = true; testData.isRunCamSplitPortConfigurated = true; testData.maxTimesOfRespDataAvailable = 0; - + bool result = rcSplitInit(); EXPECT_EQ(true, result); @@ -195,7 +195,7 @@ TEST(RCSplitTest, TestWifiModeChangeWithDeviceReady) for (uint8_t i = 0; i <= BOXCAMERA3 - BOXCAMERA1; i++) { memset(modeActivationConditionsMutable(i), 0, sizeof(modeActivationCondition_t)); } - + // bind aux1 to wifi button with range [900,1600] modeActivationConditionsMutable(0)->auxChannelIndex = 0; @@ -222,7 +222,7 @@ TEST(RCSplitTest, TestWifiModeChangeWithDeviceReady) updateActivatedModes(); // runn process loop - int8_t randNum = rand() % 127 + 6; + int8_t randNum = rand() % 127 + 6; testData.maxTimesOfRespDataAvailable = randNum; rcSplitProcess((timeUs_t)0); @@ -240,7 +240,7 @@ TEST(RCSplitTest, TestWifiModeChangeCombine) testData.isRunCamSplitOpenPortSupported = true; testData.isRunCamSplitPortConfigurated = true; testData.maxTimesOfRespDataAvailable = 0; - + bool result = rcSplitInit(); EXPECT_EQ(true, result); @@ -248,7 +248,7 @@ TEST(RCSplitTest, TestWifiModeChangeCombine) for (uint8_t i = 0; i <= BOXCAMERA3 - BOXCAMERA1; i++) { memset(modeActivationConditionsMutable(i), 0, sizeof(modeActivationCondition_t)); } - + // bind aux1 to wifi button with range [900,1600] modeActivationConditionsMutable(0)->auxChannelIndex = 0; @@ -275,7 +275,7 @@ TEST(RCSplitTest, TestWifiModeChangeCombine) updateActivatedModes(); // runn process loop - int8_t randNum = rand() % 127 + 6; + int8_t randNum = rand() % 127 + 6; testData.maxTimesOfRespDataAvailable = randNum; rcSplitProcess((timeUs_t)0); @@ -361,8 +361,8 @@ extern "C" { return NULL; } - uint32_t serialRxBytesWaiting(const serialPort_t *instance) - { + uint32_t serialRxBytesWaiting(const serialPort_t *instance) + { UNUSED(instance); testData.maxTimesOfRespDataAvailable--; @@ -373,9 +373,9 @@ extern "C" { return 0; } - uint8_t serialRead(serialPort_t *instance) - { - UNUSED(instance); + uint8_t serialRead(serialPort_t *instance) + { + UNUSED(instance); if (testData.maxTimesOfRespDataAvailable > 0) { static uint8_t i = 0; @@ -388,41 +388,41 @@ extern "C" { return buffer[i++]; } - return 0; + return 0; } - void sbufWriteString(sbuf_t *dst, const char *string) - { - UNUSED(dst); UNUSED(string); + void sbufWriteString(sbuf_t *dst, const char *string) + { + UNUSED(dst); UNUSED(string); if (testData.isAllowBufferReadWrite) { sbufWriteData(dst, string, strlen(string)); } } - void sbufWriteU8(sbuf_t *dst, uint8_t val) - { - UNUSED(dst); UNUSED(val); + void sbufWriteU8(sbuf_t *dst, uint8_t val) + { + UNUSED(dst); UNUSED(val); if (testData.isAllowBufferReadWrite) { *dst->ptr++ = val; } } - + void sbufWriteData(sbuf_t *dst, const void *data, int len) { - UNUSED(dst); UNUSED(data); UNUSED(len); + UNUSED(dst); UNUSED(data); UNUSED(len); if (testData.isAllowBufferReadWrite) { memcpy(dst->ptr, data, len); dst->ptr += len; - + } } // modifies streambuf so that written data are prepared for reading void sbufSwitchToReader(sbuf_t *buf, uint8_t *base) { - UNUSED(buf); UNUSED(base); + UNUSED(buf); UNUSED(base); if (testData.isAllowBufferReadWrite) { buf->end = buf->ptr; diff --git a/src/test/unit/rx_ibus_unittest.cc b/src/test/unit/rx_ibus_unittest.cc index 6810516bc7..bca2bee45f 100644 --- a/src/test/unit/rx_ibus_unittest.cc +++ b/src/test/unit/rx_ibus_unittest.cc @@ -250,7 +250,7 @@ protected: findSerialPortConfig_stub_retval = &serialTestInstanceConfig; EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeConfig)); - + EXPECT_TRUE(initSharedIbusTelemetryCalled); //handle that internal ibus position is not set to zero at init @@ -330,7 +330,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap const uint8_t packet_half[] = {0x20, 0x00, //length and reserved (unknown) bits 0x00, 0xab, 0x01, 0xab, 0x02, 0xab, 0x03, 0xab, 0x04, 0xab, //channel 1..5 0x05, 0xab}; - const uint8_t packet_full[] = {0x20, 0x00, //length and reserved (unknown) bits + const uint8_t packet_full[] = {0x20, 0x00, //length and reserved (unknown) bits 0x00, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x04, 0x00, //channel 1..5 0x05, 0x00, 0x06, 0x00, 0x07, 0x00, 0x08, 0x00, 0x09, 0x00, //channel 6..10 0x0a, 0x00, 0x0b, 0x00, 0x0c, 0x00, 0x0d, 0x00, //channel 11..14 @@ -343,7 +343,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap microseconds_stub_value += 5000; EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); - + for (size_t i=0; i < sizeof(packet_full); i++) { EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn()); stub_serialRxCallback(packet_full[i]); @@ -452,9 +452,9 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived_not_shared_port) TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryPacketReceived) { - uint8_t packet[] = {0x04, 0x81, 0x7a, 0xff}; //ibus sensor discovery + uint8_t packet[] = {0x04, 0x81, 0x7a, 0xff}; //ibus sensor discovery resetStubTelemetry(); - + receivePacket(packet, sizeof(packet)); //no frame complete signal to rx system, but telemetry system is called @@ -466,7 +466,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryPacketReceived) TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryIgnoreTxEchoToRx) { - uint8_t packet[] = {0x04, 0x81, 0x7a, 0xff}; //ibus sensor discovery + uint8_t packet[] = {0x04, 0x81, 0x7a, 0xff}; //ibus sensor discovery resetStubTelemetry(); stubTelemetryIgnoreRxChars = 4; @@ -475,7 +475,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryIgnoreTxEchoToRx) rxRuntimeConfig.rcFrameStatusFn(); EXPECT_TRUE(stubTelemetryCalled); - //when those four bytes are sent and looped back + //when those four bytes are sent and looped back resetStubTelemetry(); rxRuntimeConfig.rcFrameStatusFn(); receivePacket(packet, sizeof(packet)); @@ -483,7 +483,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryIgnoreTxEchoToRx) //then they are ignored EXPECT_FALSE(stubTelemetryCalled); - //and then next packet can be received + //and then next packet can be received receivePacket(packet, sizeof(packet)); rxRuntimeConfig.rcFrameStatusFn(); EXPECT_TRUE(stubTelemetryCalled); @@ -492,7 +492,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryIgnoreTxEchoToRx) TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryShouldNotIgnoreTxEchoAfterInterFrameGap) { - uint8_t packet[] = {0x04, 0x81, 0x7a, 0xff}; //ibus sensor discovery + uint8_t packet[] = {0x04, 0x81, 0x7a, 0xff}; //ibus sensor discovery resetStubTelemetry(); stubTelemetryIgnoreRxChars = 4; @@ -506,9 +506,8 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryShouldNotIgnoreTxEchoAfterInter resetStubTelemetry(); rxRuntimeConfig.rcFrameStatusFn(); - //then next packet can be received + //then next packet can be received receivePacket(packet, sizeof(packet)); rxRuntimeConfig.rcFrameStatusFn(); EXPECT_TRUE(stubTelemetryCalled); } - diff --git a/src/test/unit/rx_ranges_unittest.cc b/src/test/unit/rx_ranges_unittest.cc index 5864a6639c..45712a71aa 100644 --- a/src/test/unit/rx_ranges_unittest.cc +++ b/src/test/unit/rx_ranges_unittest.cc @@ -219,4 +219,3 @@ void failsafeOnValidDataFailed(void) } } -