remove not needed whitespaces
This commit is contained in:
parent
dfe868ef96
commit
03aa31acdd
|
@ -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 :).
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -54,11 +54,11 @@ before_script:
|
|||
|
||||
script: ./.travis.sh
|
||||
|
||||
cache:
|
||||
cache:
|
||||
directories:
|
||||
- downloads
|
||||
- tools
|
||||
|
||||
|
||||
|
||||
#notifications:
|
||||
# irc: "chat.freenode.net#cleanflight"
|
||||
|
|
|
@ -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.
|
||||
|
||||
|
||||
|
|
2
Makefile
2
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.
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -19,4 +19,3 @@ export V0 :=
|
|||
export V1 :=
|
||||
export STDOUT :=
|
||||
endif
|
||||
|
||||
|
|
|
@ -66,4 +66,4 @@ OPTIMISE_SPEED := -Ofast
|
|||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
|
||||
endif
|
||||
endif
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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 \
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -15,4 +15,3 @@ endif
|
|||
ifneq ($(OPENOCD_CFG),)
|
||||
OPENOCD_COMMAND = $(OPENOCD) -f $(OPENOCD_IF) -f $(OPENOCD_CFG)
|
||||
endif
|
||||
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
|
|
@ -38,4 +38,3 @@
|
|||
#define REQUIRE_CC_ARM_PRINTF_SUPPORT
|
||||
#define REQUIRE_PRINTF_LONG_SUPPORT
|
||||
#endif
|
||||
|
||||
|
|
|
@ -25,4 +25,3 @@ void cmsUpdate(uint32_t currentTimeUs);
|
|||
#define CMS_EXIT (0)
|
||||
#define CMS_EXIT_SAVE (1)
|
||||
#define CMS_EXIT_SAVEREBOOT (2)
|
||||
|
||||
|
|
|
@ -100,4 +100,3 @@ CMS_Menu cmsx_menuVtxRTC6705 = {
|
|||
};
|
||||
|
||||
#endif // CMS
|
||||
|
||||
|
|
|
@ -36,4 +36,3 @@ void bitArrayClr(void *array, unsigned bit)
|
|||
{
|
||||
BITARRAY_BIT_OP((uint32_t*)array, bit, &=~);
|
||||
}
|
||||
|
||||
|
|
|
@ -81,4 +81,3 @@ rgbColor24bpp_t* hsvToRgb24(const hsvColor_t* c)
|
|||
}
|
||||
return &r;
|
||||
}
|
||||
|
||||
|
|
|
@ -286,4 +286,3 @@ float firFilterDenoiseUpdate(firFilterDenoise_t *filter, float input)
|
|||
else
|
||||
return filter->movingSum / ++filter->filledCount + 1;
|
||||
}
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -282,4 +282,3 @@ const huffmanTable_t huffmanTable[HUFFMAN_TABLE_SIZE] = {
|
|||
{ 9, 0x2800 }, // 0xFF 001010000
|
||||
{ 12, 0x0000 }, // EOF 000000000000
|
||||
};
|
||||
|
||||
|
|
|
@ -282,4 +282,3 @@ float fastA2F(const char *p)
|
|||
// Return signed and scaled floating point result.
|
||||
return sign * (frac ? (value / scale) : (value * scale));
|
||||
}
|
||||
|
||||
|
|
|
@ -95,4 +95,3 @@ int32_t unittest_pidMultiWiiRewrite_DTerm[3];
|
|||
|
||||
#endif // UNIT_TEST
|
||||
#endif // SRC_MAIN_FLIGHT_PID_C_
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -1,10 +0,0 @@
|
|||
/*
|
||||
* accMpu6000.cpp
|
||||
*
|
||||
* Created on: 31 Mar 2017
|
||||
* Author: martinbudden
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
|
@ -151,4 +151,3 @@ bool fakeAccDetect(accDev_t *acc)
|
|||
return true;
|
||||
}
|
||||
#endif // USE_FAKE_ACC
|
||||
|
||||
|
|
|
@ -439,4 +439,3 @@ typedef struct {
|
|||
|
||||
|
||||
bool lsm303dlhcAccDetect(accDev_t *acc);
|
||||
|
||||
|
|
|
@ -236,4 +236,3 @@ void adcInit(const adcConfig_t *config)
|
|||
|
||||
ADC_StartConversion(adc.ADCx);
|
||||
}
|
||||
|
||||
|
|
|
@ -57,4 +57,3 @@
|
|||
// 10/16 = 0.625 ms
|
||||
|
||||
bool bmp280Detect(baroDev_t *baro);
|
||||
|
||||
|
|
|
@ -70,4 +70,3 @@ bool fakeBaroDetect(baroDev_t *baro)
|
|||
return true;
|
||||
}
|
||||
#endif // USE_FAKE_BARO
|
||||
|
||||
|
|
|
@ -20,4 +20,3 @@
|
|||
struct baroDev_s;
|
||||
bool fakeBaroDetect(struct baroDev_s *baro);
|
||||
void fakeBaroSet(int32_t pressure, int32_t temperature);
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -264,4 +264,3 @@ uint16_t i2cGetErrorCounter(void)
|
|||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -70,4 +70,3 @@ typedef struct SPIDevice_s {
|
|||
} spiDevice_t;
|
||||
|
||||
extern spiDevice_t spiDevice[SPIDEV_COUNT];
|
||||
|
||||
|
|
|
@ -63,4 +63,3 @@ bool fakeMagDetect(magDev_t *mag)
|
|||
return true;
|
||||
}
|
||||
#endif // USE_FAKE_MAG
|
||||
|
||||
|
|
|
@ -115,4 +115,3 @@ void displayInit(displayPort_t *instance, const displayPortVTable_t *vTable)
|
|||
instance->grabCount = 0;
|
||||
instance->cursorRow = -1;
|
||||
}
|
||||
|
||||
|
|
|
@ -115,4 +115,4 @@ dmaIdentifier_e dmaGetIdentifier(const DMA_Stream_TypeDef* stream)
|
|||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -49,4 +49,3 @@
|
|||
#include "target.h"
|
||||
// include template-generated macros for IO pins
|
||||
#include "io_def_generated.h"
|
||||
|
||||
|
|
|
@ -1160,4 +1160,3 @@
|
|||
# define DEFIO_PORT_USED_LIST /* empty */
|
||||
# define DEFIO_PORT_OFFSET_LIST /* empty */
|
||||
#endif
|
||||
|
||||
|
|
|
@ -18,4 +18,3 @@ enum rcc_reg {
|
|||
|
||||
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
|
||||
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
|
||||
|
||||
|
|
|
@ -1,4 +1,3 @@
|
|||
#pragma once
|
||||
|
||||
typedef uint8_t rccPeriphTag_t;
|
||||
|
||||
|
|
|
@ -67,4 +67,3 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"ESCSERIAL",
|
||||
"CAMERA_CONTROL",
|
||||
};
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -144,4 +144,3 @@ uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *ret
|
|||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -47,4 +47,3 @@ void tcpDataOut(tcpPort_t *instance);
|
|||
bool tcpIsStart(void);
|
||||
bool* tcpGetUsed(void);
|
||||
tcpPort_t* tcpGetPool(void);
|
||||
|
||||
|
|
|
@ -39,4 +39,3 @@ typedef struct beeperDevConfig_s {
|
|||
void systemBeep(bool on);
|
||||
void systemBeepToggle(void);
|
||||
void beeperInit(const beeperDevConfig_t *beeperDevConfig);
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -145,6 +145,3 @@ extern const char * const lookupTableBaroHardware[];
|
|||
|
||||
extern const char * const lookupTableMagHardware[];
|
||||
//extern const uint8_t lookupTableMagHardwareEntryCount;
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -89,7 +89,3 @@ void failsafeOnRxResume(void);
|
|||
|
||||
void failsafeOnValidDataReceived(void);
|
||||
void failsafeOnValidDataFailed(void);
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -528,4 +528,3 @@ void imuSetHasNewData(uint32_t dt)
|
|||
IMU_UNLOCK;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -80,5 +80,3 @@ void imuSetAttitudeQuat(float w, float x, float y, float z);
|
|||
void imuSetHasNewData(uint32_t dt);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -45,4 +45,3 @@ typedef struct ioMem_s {
|
|||
uint8_t D_FLASH_ADDR_L;
|
||||
uint8_t *D_PTR_I;
|
||||
} ioMem_t;
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -16,4 +16,3 @@
|
|||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
|
|
|
@ -83,5 +83,3 @@ void warningLedUpdate(void)
|
|||
|
||||
warningLedRefresh();
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -42,4 +42,3 @@ extern const char * const rtc6705PowerNames[RTC6705_POWER_COUNT];
|
|||
|
||||
void vtxRTC6705Configure(void);
|
||||
bool vtxRTC6705Init();
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -18,4 +18,3 @@
|
|||
#pragma once
|
||||
|
||||
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
||||
|
|
|
@ -300,4 +300,3 @@ void cx10Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
|
|||
cx10Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -300,4 +300,3 @@ void symaNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
|
|||
symaNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -64,4 +64,3 @@ void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -384,4 +384,3 @@ bool srxlRxIsActive(void)
|
|||
}
|
||||
|
||||
#endif // SERIAL_RX
|
||||
|
||||
|
|
|
@ -79,4 +79,3 @@ void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims);
|
|||
union flightDynamicsTrims_u;
|
||||
void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse);
|
||||
void setAccelerationFilter(uint16_t initialAccLpfCutHz);
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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 {
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -8,4 +8,3 @@ TARGET_SRC = \
|
|||
drivers/barometer/barometer_ms5611.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/inverter.c
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
};
|
||||
|
||||
|
|
|
@ -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) )
|
||||
|
||||
|
|
|
@ -7,4 +7,3 @@ TARGET_SRC = \
|
|||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/compass/compass_ak8963.c
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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) )
|
||||
|
||||
|
|
|
@ -83,4 +83,3 @@ void targetConfiguration(void)
|
|||
compassConfigMutable()->mag_hardware = MAG_DEFAULT;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -52,4 +52,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0),
|
||||
};
|
||||
|
||||
|
|
|
@ -228,4 +228,3 @@
|
|||
*/
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 5
|
||||
#define USED_TIMERS ( TIM_N(3) | TIM_N(8) | TIM_N(5) )
|
||||
|
||||
|
|
|
@ -18,4 +18,3 @@
|
|||
* support for CAN
|
||||
* SD card logging (SPI)
|
||||
* 3 AD channels, one with 10k/1k divider, two with 1k series resistor
|
||||
|
||||
|
|
|
@ -8,4 +8,3 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_hal.c
|
||||
|
||||
|
|
|
@ -16,4 +16,3 @@
|
|||
* external SPI (shared with U4/5)
|
||||
* 128Mb dataflash logging (SPI)
|
||||
* Voltage measurement, with 10k/1k divider
|
||||
|
||||
|
|
|
@ -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
|
||||
};
|
||||
|
||||
|
|
|
@ -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
|
||||
};
|
||||
|
||||
|
|
|
@ -117,4 +117,3 @@
|
|||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 4
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(8) | TIM_N(15) )
|
||||
|
||||
|
|
|
@ -7,4 +7,3 @@ TARGET_SRC = \
|
|||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/vtx_rtc6705_soft_spi.c \
|
||||
drivers/max7456.c
|
||||
|
||||
|
|
|
@ -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
|
||||
More info to come
|
||||
|
|
|
@ -74,4 +74,3 @@ void targetPreInit(void)
|
|||
IOHi(sdcardIo);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -40,4 +40,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1) // S6_OUT
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -8,4 +8,3 @@ TARGET_SRC = \
|
|||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_ms5611.c \
|
||||
drivers/compass/compass_hmc5883l.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
|
||||
};
|
||||
|
||||
|
|
|
@ -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))
|
||||
|
||||
|
|
|
@ -15,4 +15,3 @@ TARGET_SRC = \
|
|||
drivers/barometer/barometer_ms5611.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/compass/compass_ak8975.c
|
||||
|
||||
|
|
|
@ -41,4 +41,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0 ) // PWM14 - OUT6
|
||||
|
||||
};
|
||||
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue