mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 01:35:41 +03:00
Rebased on to master (conflict in Makefile)
This commit is contained in:
commit
6c5997ef9f
133 changed files with 3020 additions and 412 deletions
|
@ -64,7 +64,14 @@ elif [ $TARGET ] ; then
|
|||
fi
|
||||
|
||||
elif [ $GOAL ] ; then
|
||||
make V=0 $GOAL
|
||||
make V=0 $GOAL || exit $?
|
||||
|
||||
if [ "test" == "$GOAL" ] ; then
|
||||
lcov --directory . -b src/test --capture --output-file coverage.info 2>&1 | grep -E ":version '402\*', prefer.*'406\*" --invert-match
|
||||
lcov --remove coverage.info 'lib/test/*' 'src/test/*' '/usr/*' --output-file coverage.info # filter out system and test code
|
||||
lcov --list coverage.info # debug before upload
|
||||
coveralls-lcov coverage.info # uploads to coveralls
|
||||
fi
|
||||
|
||||
else
|
||||
make V=0 all
|
||||
|
|
10
.travis.yml
10
.travis.yml
|
@ -27,12 +27,21 @@ git:
|
|||
addons:
|
||||
apt:
|
||||
packages:
|
||||
- lcov
|
||||
- build-essential
|
||||
- git
|
||||
- libc6-i386
|
||||
- time
|
||||
|
||||
# We use cpp for unit tests, and c for the main project.
|
||||
language: cpp
|
||||
compiler: clang
|
||||
dist: trusty
|
||||
|
||||
|
||||
before_install:
|
||||
- pip install --user cpp-coveralls
|
||||
- gem install coveralls-lcov
|
||||
|
||||
install:
|
||||
- make arm_sdk_install
|
||||
|
@ -41,6 +50,7 @@ before_script:
|
|||
- tools/gcc-arm-none-eabi-6-2017-q1-update/bin/arm-none-eabi-gcc --version
|
||||
- clang --version
|
||||
- clang++ --version
|
||||
- gcc --version
|
||||
|
||||
script: ./.travis.sh
|
||||
|
||||
|
|
55
Makefile
55
Makefile
|
@ -276,14 +276,14 @@ STARTUP_SRC = startup_stm32f30x_md_gcc.S
|
|||
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
|
||||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
|
||||
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \
|
||||
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c))
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F30x
|
||||
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \
|
||||
$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F30x/*.c))
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(CMSIS_DIR)/CM1/CoreSupport \
|
||||
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x
|
||||
$(CMSIS_DIR)/CM4/CoreSupport \
|
||||
$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F30x
|
||||
|
||||
ifneq ($(filter VCP, $(FEATURES)),)
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
|
@ -817,7 +817,7 @@ endif
|
|||
SPEED_OPTIMISED_SRC := ""
|
||||
SIZE_OPTIMISED_SRC := ""
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
|
||||
ifneq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
|
||||
SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
||||
common/encoding.c \
|
||||
common/filter.c \
|
||||
|
@ -911,7 +911,7 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
|||
io/vtx_rtc6705.c \
|
||||
io/vtx_smartaudio.c \
|
||||
io/vtx_tramp.c
|
||||
endif #F3
|
||||
endif #!F1
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
|
||||
VCP_SRC = \
|
||||
|
@ -1015,6 +1015,11 @@ SITLEXCLUDES = \
|
|||
drivers/rcc.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/rx_xn297.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
telemetry/crsf.c \
|
||||
telemetry/srxl.c \
|
||||
io/displayport_oled.c
|
||||
|
||||
|
||||
# check if target.mk supplied
|
||||
|
@ -1030,12 +1035,20 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(SITL_TARGETS)))
|
|||
SRC := $(TARGET_SRC) $(SITL_SRC) $(VARIANT_SRC)
|
||||
endif
|
||||
|
||||
ifneq ($(filter $(TARGET),$(F4_TARGETS) $(F7_TARGETS)),)
|
||||
ifneq ($(filter $(TARGET),$(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),)
|
||||
DSPLIB := $(ROOT)/lib/main/DSP_Lib
|
||||
DEVICE_FLAGS += -DARM_MATH_CM4 -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE
|
||||
|
||||
ifneq ($(filter $(TARGET),$(F3_TARGETS)) $(F4_TARGETS)),)
|
||||
DEVICE_FLAGS += -DARM_MATH_CM4
|
||||
endif
|
||||
ifneq ($(filter $(TARGET),$(F7_TARGETS)),)
|
||||
DEVICE_FLAGS += -DARM_MATH_CM7
|
||||
endif
|
||||
|
||||
INCLUDE_DIRS += $(DSPLIB)/Include
|
||||
|
||||
SRC += $(DSPLIB)/Source/BasicMathFunctions/arm_mult_f32.c
|
||||
SRC += $(DSPLIB)/Source/TransformFunctions/arm_rfft_fast_f32.c
|
||||
SRC += $(DSPLIB)/Source/TransformFunctions/arm_cfft_f32.c
|
||||
SRC += $(DSPLIB)/Source/TransformFunctions/arm_rfft_fast_init_f32.c
|
||||
|
@ -1046,6 +1059,7 @@ SRC += $(DSPLIB)/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
|
|||
SRC += $(DSPLIB)/Source/StatisticsFunctions/arm_max_f32.c
|
||||
|
||||
SRC += $(wildcard $(DSPLIB)/Source/*/*.S)
|
||||
|
||||
endif
|
||||
|
||||
|
||||
|
@ -1115,13 +1129,6 @@ OPTIMISE_DEFAULT := -Os
|
|||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT)
|
||||
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
|
||||
OPTIMISE_DEFAULT := -O2
|
||||
OPTIMISE_SPEED := -Ofast
|
||||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
|
||||
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(SITL_TARGETS)))
|
||||
OPTIMISE_DEFAULT := -Ofast
|
||||
OPTIMISE_SPEED := -Ofast
|
||||
|
@ -1130,9 +1137,11 @@ OPTIMISE_SIZE := -Os
|
|||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
|
||||
|
||||
else
|
||||
OPTIMISE_DEFAULT := -Ofast
|
||||
OPTIMISE_DEFAULT := -O2
|
||||
OPTIMISE_SPEED := -Ofast
|
||||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT)
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
|
||||
|
||||
endif #TARGETS
|
||||
|
||||
|
@ -1141,7 +1150,7 @@ CC_SPEED_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
|
|||
CC_SIZE_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SIZE)
|
||||
|
||||
else #DEBUG
|
||||
OPTIMISE_DEFAULT := -O0
|
||||
OPTIMISE_DEFAULT := -Og
|
||||
|
||||
CC_DEBUG_OPTIMISATION := $(OPTIMISE_DEFAULT)
|
||||
|
||||
|
@ -1199,12 +1208,16 @@ LDFLAGS = \
|
|||
$(ARCH_FLAGS) \
|
||||
$(LTO_FLAGS) \
|
||||
$(DEBUG_FLAGS) \
|
||||
-static \
|
||||
-static-libgcc \
|
||||
-Wl,-gc-sections,-Map,$(TARGET_MAP) \
|
||||
-Wl,-L$(LINKER_DIR) \
|
||||
-Wl,--cref \
|
||||
-T$(LD_SCRIPT)
|
||||
|
||||
ifneq ($(filter SITL_STATIC,$(OPTIONS)),)
|
||||
LDFLAGS += \
|
||||
-static \
|
||||
-static-libgcc
|
||||
endif
|
||||
endif
|
||||
|
||||
###############################################################################
|
||||
|
|
1439
Makefile.orig
Normal file
1439
Makefile.orig
Normal file
File diff suppressed because it is too large
Load diff
|
@ -71,6 +71,10 @@ https://travis-ci.org/betaflight/betaflight
|
|||
|
||||
[](https://travis-ci.org/betaflight/betaflight)
|
||||
|
||||
Coveralls is used to monitor code coverage: https://coveralls.io/github/betaflight/betaflight
|
||||
|
||||
[](https://coveralls.io/github/betaflight/betaflight?branch=master)
|
||||
|
||||
## Betaflight Releases
|
||||
|
||||
https://github.com/betaflight/betaflight/releases
|
||||
|
|
|
@ -31,7 +31,7 @@ __attribute__( ( always_inline ) ) static inline void __set_BASEPRI_MAX_nb(uint3
|
|||
__ASM volatile ("\tMSR basepri_max, %0\n" : : "r" (basePri) );
|
||||
}
|
||||
|
||||
#if !defined(STM32F4) && !defined(STM32F7) /* already defined in /lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h for F4 targets */
|
||||
#if !defined(STM32F3) && !defined(STM32F4) && !defined(STM32F7) /* already defined in /lib/main/CMSIS/CM4/CoreSupport/core_cmFunc.h for F4 targets */
|
||||
__attribute__( ( always_inline ) ) static inline void __set_BASEPRI_MAX(uint32_t basePri)
|
||||
{
|
||||
__ASM volatile ("\tMSR basepri_max, %0\n" : : "r" (basePri) : "memory" );
|
||||
|
|
|
@ -65,5 +65,8 @@ typedef enum {
|
|||
DEBUG_ESC_SENSOR_RPM,
|
||||
DEBUG_ESC_SENSOR_TMP,
|
||||
DEBUG_ALTITUDE,
|
||||
DEBUG_FFT,
|
||||
DEBUG_FFT_TIME,
|
||||
DEBUG_FFT_FREQ,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -26,11 +26,9 @@
|
|||
|
||||
#define M_LN2_FLOAT 0.69314718055994530942f
|
||||
#define M_PI_FLOAT 3.14159265358979323846f
|
||||
|
||||
#define BIQUAD_BANDWIDTH 1.9f /* bandwidth in octaves */
|
||||
#define BIQUAD_Q 1.0f / sqrtf(2.0f) /* quality factor - butterworth*/
|
||||
|
||||
|
||||
// NULL filter
|
||||
|
||||
float nullFilterApply(void *filter, float input)
|
||||
|
@ -79,22 +77,22 @@ void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refr
|
|||
{
|
||||
biquadFilterInit(filter, filterFreq, refreshRate, BIQUAD_Q, FILTER_LPF);
|
||||
}
|
||||
|
||||
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType)
|
||||
{
|
||||
// setup variables
|
||||
const float sampleRate = 1 / ((float)refreshRate * 0.000001f);
|
||||
const float omega = 2 * M_PI_FLOAT * filterFreq / sampleRate;
|
||||
const float omega = 2.0f * M_PI_FLOAT * filterFreq * refreshRate * 0.000001f;
|
||||
const float sn = sinf(omega);
|
||||
const float cs = cosf(omega);
|
||||
const float alpha = sn / (2 * Q);
|
||||
const float alpha = sn / (2.0f * Q);
|
||||
|
||||
float b0 = 0, b1 = 0, b2 = 0, a0 = 0, a1 = 0, a2 = 0;
|
||||
|
||||
switch (filterType) {
|
||||
case FILTER_LPF:
|
||||
b0 = (1 - cs) / 2;
|
||||
b0 = (1 - cs) * 0.5f;
|
||||
b1 = 1 - cs;
|
||||
b2 = (1 - cs) / 2;
|
||||
b2 = (1 - cs) * 0.5f;
|
||||
a0 = 1 + alpha;
|
||||
a1 = -2 * cs;
|
||||
a2 = 1 - alpha;
|
||||
|
@ -107,6 +105,14 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh
|
|||
a1 = -2 * cs;
|
||||
a2 = 1 - alpha;
|
||||
break;
|
||||
case FILTER_BPF:
|
||||
b0 = alpha;
|
||||
b1 = 0;
|
||||
b2 = -alpha;
|
||||
a0 = 1 + alpha;
|
||||
a1 = -2 * cs;
|
||||
a2 = 1 - alpha;
|
||||
break;
|
||||
}
|
||||
|
||||
// precompute the coefficients
|
||||
|
@ -117,10 +123,50 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh
|
|||
filter->a2 = a2 / a0;
|
||||
|
||||
// zero initial samples
|
||||
filter->x1 = filter->x2 = 0;
|
||||
filter->y1 = filter->y2 = 0;
|
||||
filter->d1 = filter->d2 = 0;
|
||||
}
|
||||
|
||||
/* Computes a biquadFilter_t filter on a sample */
|
||||
void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType)
|
||||
{
|
||||
// backup state
|
||||
float x1 = filter->x1;
|
||||
float x2 = filter->x2;
|
||||
float y1 = filter->y1;
|
||||
float y2 = filter->y2;
|
||||
float d1 = filter->d1;
|
||||
float d2 = filter->d2;
|
||||
|
||||
biquadFilterInit(filter, filterFreq, refreshRate, Q, filterType);
|
||||
|
||||
// restore state
|
||||
filter->x1 = x1;
|
||||
filter->x2 = x2;
|
||||
filter->y1 = y1;
|
||||
filter->y2 = y2;
|
||||
filter->d1 = d1;
|
||||
filter->d2 = d2;
|
||||
}
|
||||
|
||||
/* Computes a biquadFilter_t filter on a sample (slightly less precise than df2 but works in dynamic mode) */
|
||||
float biquadFilterApplyDF1(biquadFilter_t *filter, float input)
|
||||
{
|
||||
/* compute result */
|
||||
const float result = filter->b0 * input + filter->b1 * filter->x1 + filter->b2 * filter->x2 - filter->a1 * filter->y1 - filter->a2 * filter->y2;
|
||||
|
||||
/* shift x1 to x2, input to x1 */
|
||||
filter->x2 = filter->x1;
|
||||
filter->x1 = input;
|
||||
|
||||
/* shift y1 to y2, result to y1 */
|
||||
filter->y2 = filter->y1;
|
||||
filter->y1 = result;
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/* Computes a biquadFilter_t filter in direct form 2 on a sample (higher precision but can't handle changes in coefficients */
|
||||
float biquadFilterApply(biquadFilter_t *filter, float input)
|
||||
{
|
||||
const float result = filter->b0 * input + filter->d1;
|
||||
|
|
|
@ -33,6 +33,7 @@ typedef struct pt1Filter_s {
|
|||
/* this holds the data required to update samples thru a filter */
|
||||
typedef struct biquadFilter_s {
|
||||
float b0, b1, b2, a1, a2;
|
||||
float x1, x2, y1, y2;
|
||||
float d1, d2;
|
||||
} biquadFilter_t;
|
||||
|
||||
|
@ -52,7 +53,8 @@ typedef enum {
|
|||
|
||||
typedef enum {
|
||||
FILTER_LPF,
|
||||
FILTER_NOTCH
|
||||
FILTER_NOTCH,
|
||||
FILTER_BPF,
|
||||
} biquadFilterType_e;
|
||||
|
||||
typedef struct firFilter_s {
|
||||
|
@ -71,9 +73,14 @@ float nullFilterApply(void *filter, float input);
|
|||
|
||||
void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate);
|
||||
void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
|
||||
void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
|
||||
float biquadFilterApplyDF1(biquadFilter_t *filter, float input);
|
||||
float biquadFilterApply(biquadFilter_t *filter, float input);
|
||||
float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff);
|
||||
|
||||
// not exactly correct, but very very close and much much faster
|
||||
#define filterGetNotchQApprox(centerFreq, cutoff) ((float)(cutoff * centerFreq) / ((float)(centerFreq - cutoff) * (float)(centerFreq + cutoff)))
|
||||
|
||||
void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT);
|
||||
float pt1FilterApply(pt1Filter_t *filter, float input);
|
||||
float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT);
|
||||
|
|
|
@ -105,7 +105,8 @@
|
|||
#define PG_VCD_CONFIG 514
|
||||
#define PG_VTX_CONFIG 515
|
||||
#define PG_SONAR_CONFIG 516
|
||||
#define PG_BETAFLIGHT_END 516
|
||||
#define PG_ESC_SENSOR_CONFIG 517
|
||||
#define PG_BETAFLIGHT_END 517
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
|
|
|
@ -38,8 +38,12 @@
|
|||
#define ADC_INSTANCE ADC1
|
||||
#endif
|
||||
|
||||
#ifndef ADC1_DMA_STREAM
|
||||
#define ADC1_DMA_STREAM DMA2_Stream4
|
||||
#endif
|
||||
|
||||
const adcDevice_t adcHardware[] = {
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_CHANNEL_0 },
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = ADC1_DMA_STREAM, .channel = DMA_CHANNEL_0 },
|
||||
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
|
||||
};
|
||||
|
||||
|
|
|
@ -146,7 +146,7 @@ uint32_t IO_EXTI_Line(IO_t io)
|
|||
#elif defined(STM32F7)
|
||||
return 1 << IO_GPIOPinIdx(io);
|
||||
#elif defined(SIMULATOR_BUILD)
|
||||
return 1;
|
||||
return 0;
|
||||
#else
|
||||
# error "Unknown target type"
|
||||
#endif
|
||||
|
@ -353,9 +353,20 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if DEFIO_PORT_USED_COUNT > 0
|
||||
static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST };
|
||||
static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST };
|
||||
#else
|
||||
// Avoid -Wpedantic warning
|
||||
static const uint16_t ioDefUsedMask[1] = {0};
|
||||
static const uint8_t ioDefUsedOffset[1] = {0};
|
||||
#endif
|
||||
#if DEFIO_IO_USED_COUNT
|
||||
ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||
#else
|
||||
// Avoid -Wpedantic warning
|
||||
ioRec_t ioRecs[1];
|
||||
#endif
|
||||
|
||||
// initialize all ioRec_t structures from ROM
|
||||
// currently only bitmask is used, this may change in future
|
||||
|
|
|
@ -16,7 +16,8 @@
|
|||
*/
|
||||
|
||||
#pragma once
|
||||
// this file is automatically generated by def_generated.pl script
|
||||
|
||||
// this file is automatically generated by src/utils/def_generated.pl script
|
||||
// do not modify this file directly, your changes will be lost
|
||||
|
||||
// DEFIO_PORT_<port>_USED_MASK is bitmask of used pins on target
|
||||
|
@ -96,7 +97,8 @@
|
|||
#define DEFIO_GPIOID__F 5
|
||||
#define DEFIO_GPIOID__G 6
|
||||
|
||||
// DEFIO_TAG__P<port><pin> will expand to TAG if defined for target
|
||||
// DEFIO_TAG__P<port><pin> will expand to TAG if defined for target, error is triggered otherwise
|
||||
// DEFIO_TAG_E__P<port><pin> will expand to TAG if defined, to NONE otherwise (usefull for tables that are CPU-specific)
|
||||
// DEFIO_REC__P<port><pin> will expand to ioRec* (using DEFIO_REC_INDEX(idx))
|
||||
|
||||
#if DEFIO_PORT_A_USED_MASK & BIT(0)
|
||||
|
@ -1150,8 +1152,10 @@
|
|||
# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET
|
||||
#endif
|
||||
|
||||
#if !defined DEFIO_PORT_USED_LIST
|
||||
# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h"
|
||||
#if !defined(DEFIO_PORT_USED_LIST)
|
||||
# if !defined DEFIO_NO_PORTS // supress warnings if we really don't want any pins
|
||||
# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target.h"
|
||||
# endif
|
||||
# define DEFIO_PORT_USED_COUNT 0
|
||||
# define DEFIO_PORT_USED_LIST /* empty */
|
||||
# define DEFIO_PORT_OFFSET_LIST /* empty */
|
||||
|
|
|
@ -33,7 +33,7 @@ typedef struct ioRec_s {
|
|||
uint8_t index;
|
||||
} ioRec_t;
|
||||
|
||||
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
|
||||
extern ioRec_t ioRecs[];
|
||||
|
||||
int IO_GPIOPortIdx(IO_t io);
|
||||
int IO_GPIOPinIdx(IO_t io);
|
||||
|
|
|
@ -139,7 +139,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
|||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||
TIM_Cmd(timer, DISABLE);
|
||||
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1);
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((timerClock(timer) / getDshotHz(pwmProtocolType)) - 1);
|
||||
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
|
||||
|
|
|
@ -123,7 +123,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
|||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||
|
||||
motor->TimHandle.Instance = timerHardware->tim;
|
||||
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;
|
||||
motor->TimHandle.Init.Prescaler = (timerClock(timer) / getDshotHz(pwmProtocolType)) - 1;;
|
||||
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
|
||||
motor->TimHandle.Init.RepetitionCounter = 0;
|
||||
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
|
|
|
@ -118,17 +118,30 @@ static void setTxSignal(softSerial_t *softSerial, uint8_t state)
|
|||
}
|
||||
}
|
||||
|
||||
static void serialEnableCC(softSerial_t *softSerial)
|
||||
{
|
||||
#ifdef USE_HAL_DRIVER
|
||||
TIM_CCxChannelCmd(softSerial->timerHardware->tim, softSerial->timerHardware->channel, TIM_CCx_ENABLE);
|
||||
#else
|
||||
TIM_CCxCmd(softSerial->timerHardware->tim, softSerial->timerHardware->channel, TIM_CCx_Enable);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void serialInputPortActivate(softSerial_t *softSerial)
|
||||
{
|
||||
if (softSerial->port.options & SERIAL_INVERTED) {
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_IPD);
|
||||
#elif defined(STM32F7)
|
||||
IOConfigGPIOAF(softSerial->rxIO, IOCFG_AF_PP_PD, softSerial->timerHardware->alternateFunction);
|
||||
#else
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_AF_PP_PD);
|
||||
#endif
|
||||
} else {
|
||||
#ifdef STM32F1
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_IPU);
|
||||
#elif defined(STM32F7)
|
||||
IOConfigGPIOAF(softSerial->rxIO, IOCFG_AF_PP_UP, softSerial->timerHardware->alternateFunction);
|
||||
#else
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_AF_PP_UP);
|
||||
#endif
|
||||
|
@ -140,11 +153,7 @@ static void serialInputPortActivate(softSerial_t *softSerial)
|
|||
|
||||
// Enable input capture
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
TIM_CCxChannelCmd(softSerial->timerHardware->tim, softSerial->timerHardware->channel, TIM_CCx_ENABLE);
|
||||
#else
|
||||
TIM_CCxCmd(softSerial->timerHardware->tim, softSerial->timerHardware->channel, TIM_CCx_Enable);
|
||||
#endif
|
||||
serialEnableCC(softSerial);
|
||||
}
|
||||
|
||||
static void serialInputPortDeActivate(softSerial_t *softSerial)
|
||||
|
@ -157,18 +166,36 @@ static void serialInputPortDeActivate(softSerial_t *softSerial)
|
|||
TIM_CCxCmd(softSerial->timerHardware->tim, softSerial->timerHardware->channel, TIM_CCx_Disable);
|
||||
#endif
|
||||
|
||||
#ifdef STM32F7
|
||||
IOConfigGPIOAF(softSerial->rxIO, IOCFG_IN_FLOATING, softSerial->timerHardware->alternateFunction);
|
||||
#else
|
||||
IOConfigGPIO(softSerial->rxIO, IOCFG_IN_FLOATING);
|
||||
#endif
|
||||
softSerial->rxActive = false;
|
||||
}
|
||||
|
||||
static void serialOutputPortActivate(softSerial_t *softSerial)
|
||||
{
|
||||
#ifdef STM32F7
|
||||
if (softSerial->exTimerHardware)
|
||||
IOConfigGPIOAF(softSerial->txIO, IOCFG_OUT_PP, softSerial->exTimerHardware->alternateFunction);
|
||||
else
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_OUT_PP);
|
||||
#else
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_OUT_PP);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void serialOutputPortDeActivate(softSerial_t *softSerial)
|
||||
{
|
||||
#ifdef STM32F7
|
||||
if (softSerial->exTimerHardware)
|
||||
IOConfigGPIOAF(softSerial->txIO, IOCFG_IN_FLOATING, softSerial->exTimerHardware->alternateFunction);
|
||||
else
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_IN_FLOATING);
|
||||
#else
|
||||
IOConfigGPIO(softSerial->txIO, IOCFG_IN_FLOATING);
|
||||
#endif
|
||||
}
|
||||
|
||||
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
|
||||
|
@ -199,22 +226,6 @@ static void serialTimerConfigureTimebase(const timerHardware_t *timerHardwarePtr
|
|||
timerConfigure(timerHardwarePtr, timerPeriod, mhz);
|
||||
}
|
||||
|
||||
#if 0
|
||||
static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||
{
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure;
|
||||
|
||||
TIM_ICStructInit(&TIM_ICInitStructure);
|
||||
TIM_ICInitStructure.TIM_Channel = channel;
|
||||
TIM_ICInitStructure.TIM_ICPolarity = polarity;
|
||||
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
||||
|
||||
TIM_ICInit(tim, &TIM_ICInitStructure);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void resetBuffers(softSerial_t *softSerial)
|
||||
{
|
||||
softSerial->port.rxBufferSize = SOFTSERIAL_BUFFER_SIZE;
|
||||
|
@ -414,6 +425,7 @@ void prepareForNextRxByte(softSerial_t *softSerial)
|
|||
if (softSerial->rxEdge == LEADING) {
|
||||
softSerial->rxEdge = TRAILING;
|
||||
timerChConfigIC(softSerial->timerHardware, (softSerial->port.options & SERIAL_INVERTED) ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);
|
||||
serialEnableCC(softSerial);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -511,6 +523,9 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
|||
}
|
||||
|
||||
timerChConfigIC(self->timerHardware, inverted ? ICPOLARITY_FALLING : ICPOLARITY_RISING, 0);
|
||||
#ifdef STM32F7
|
||||
serialEnableCC(self);
|
||||
#endif
|
||||
self->rxEdge = LEADING;
|
||||
|
||||
self->rxBitIndex = 0;
|
||||
|
@ -533,6 +548,9 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
|||
self->rxEdge = TRAILING;
|
||||
timerChConfigIC(self->timerHardware, inverted ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);
|
||||
}
|
||||
#ifdef STM32F7
|
||||
serialEnableCC(self);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -37,9 +37,9 @@
|
|||
|
||||
#define BASE_PORT 5760
|
||||
|
||||
const struct serialPortVTable uartVTable[]; // Forward
|
||||
static const struct serialPortVTable tcpVTable; // Forward
|
||||
static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT];
|
||||
static bool portInited[SERIAL_PORT_COUNT];
|
||||
static bool tcpPortInitialized[SERIAL_PORT_COUNT];
|
||||
static bool tcpStart = false;
|
||||
bool tcpIsStart(void) {
|
||||
return tcpStart;
|
||||
|
@ -76,8 +76,8 @@ static void onAccept(dyad_Event *e) {
|
|||
}
|
||||
static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
|
||||
{
|
||||
if(portInited[id]) {
|
||||
fprintf(stderr, "port had initialed!!\n");
|
||||
if(tcpPortInitialized[id]) {
|
||||
fprintf(stderr, "port is already initialized!\n");
|
||||
return s;
|
||||
}
|
||||
|
||||
|
@ -93,7 +93,7 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
|
|||
}
|
||||
|
||||
tcpStart = true;
|
||||
portInited[id] = true;
|
||||
tcpPortInitialized[id] = true;
|
||||
|
||||
s->connected = false;
|
||||
s->clientCount = 0;
|
||||
|
@ -111,18 +111,19 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
|
|||
return s;
|
||||
}
|
||||
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
tcpPort_t *s = NULL;
|
||||
|
||||
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8)
|
||||
uintptr_t id = ((uintptr_t)USARTx - 1);
|
||||
if(id >= 0 && id < SERIAL_PORT_COUNT) {
|
||||
s = tcpReconfigure(&tcpSerialPorts[id], id);
|
||||
#else
|
||||
return (serialPort_t *)s;
|
||||
}
|
||||
#endif
|
||||
if(!s)
|
||||
return NULL;
|
||||
|
||||
s->port.vTable = uartVTable;
|
||||
s->port.vTable = &tcpVTable;
|
||||
|
||||
// common serial initialisation code should move to serialPort::init()
|
||||
s->port.rxBufferHead = s->port.rxBufferTail = 0;
|
||||
|
@ -167,10 +168,10 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
|
|||
} else {
|
||||
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
|
||||
}
|
||||
bytesUsed = (s->port.txBufferSize - 1) - bytesUsed;
|
||||
uint32_t bytesFree = (s->port.txBufferSize - 1) - bytesUsed;
|
||||
pthread_mutex_unlock(&s->txLock);
|
||||
|
||||
return bytesUsed;
|
||||
return bytesFree;
|
||||
}
|
||||
|
||||
bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
|
||||
|
@ -217,18 +218,19 @@ void tcpWrite(serialPort_t *instance, uint8_t ch)
|
|||
|
||||
void tcpDataOut(tcpPort_t *instance)
|
||||
{
|
||||
uint32_t bytesUsed;
|
||||
tcpPort_t *s = (tcpPort_t *)instance;
|
||||
if(s->conn == NULL) return;
|
||||
pthread_mutex_lock(&s->txLock);
|
||||
|
||||
if (s->port.txBufferHead < s->port.txBufferTail) {
|
||||
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
|
||||
dyad_write(s->conn, (const void *)(s->port.txBuffer + s->port.txBufferTail), s->port.txBufferSize - s->port.txBufferTail);
|
||||
// send data till end of buffer
|
||||
int chunk = s->port.txBufferSize - s->port.txBufferTail;
|
||||
dyad_write(s->conn, (const void *)&s->port.txBuffer[s->port.txBufferTail], chunk);
|
||||
s->port.txBufferTail = 0;
|
||||
}
|
||||
bytesUsed = s->port.txBufferHead - s->port.txBufferTail;
|
||||
dyad_write(s->conn, (const void *)(&(s->port.txBuffer[s->port.txBufferTail])), bytesUsed);
|
||||
int chunk = s->port.txBufferHead - s->port.txBufferTail;
|
||||
if(chunk)
|
||||
dyad_write(s->conn, (const void*)&s->port.txBuffer[s->port.txBufferTail], chunk);
|
||||
s->port.txBufferTail = s->port.txBufferHead;
|
||||
|
||||
pthread_mutex_unlock(&s->txLock);
|
||||
|
@ -252,8 +254,7 @@ void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size)
|
|||
// printf("\n");
|
||||
}
|
||||
|
||||
const struct serialPortVTable uartVTable[] = {
|
||||
{
|
||||
static const struct serialPortVTable tcpVTable = {
|
||||
.serialWrite = tcpWrite,
|
||||
.serialTotalRxWaiting = tcpTotalRxBytesWaiting,
|
||||
.serialTotalTxFree = tcpTotalTxBytesFree,
|
||||
|
@ -264,5 +265,4 @@ const struct serialPortVTable uartVTable[] = {
|
|||
.writeBuf = NULL,
|
||||
.beginWrite = NULL,
|
||||
.endWrite = NULL,
|
||||
}
|
||||
};
|
||||
|
|
|
@ -20,19 +20,14 @@
|
|||
#include <netinet/in.h>
|
||||
#include <pthread.h>
|
||||
#include "dyad.h"
|
||||
// Since serial ports can be used for any function these buffer sizes should be equal
|
||||
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
|
||||
|
||||
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
|
||||
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
|
||||
// increase size further.
|
||||
#define RX_BUFFER_SIZE 1400
|
||||
#define TX_BUFFER_SIZE 1400
|
||||
|
||||
typedef struct {
|
||||
serialPort_t port;
|
||||
volatile uint8_t rxBuffer[RX_BUFFER_SIZE];
|
||||
volatile uint8_t txBuffer[TX_BUFFER_SIZE];
|
||||
uint8_t rxBuffer[RX_BUFFER_SIZE];
|
||||
uint8_t txBuffer[TX_BUFFER_SIZE];
|
||||
|
||||
dyad_Stream *serv;
|
||||
dyad_Stream *conn;
|
||||
|
@ -43,16 +38,11 @@ typedef struct {
|
|||
uint8_t id;
|
||||
} tcpPort_t;
|
||||
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
|
||||
// tcpPort API
|
||||
void tcpWrite(serialPort_t *instance, uint8_t ch);
|
||||
void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size);
|
||||
uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance);
|
||||
uint32_t tcpTotalTxBytesFree(const serialPort_t *instance);
|
||||
uint8_t tcpRead(serialPort_t *instance);
|
||||
void tcpDataOut(tcpPort_t *instance);
|
||||
bool isTcpTransmitBufferEmpty(const serialPort_t *s);
|
||||
|
||||
bool tcpIsStart(void);
|
||||
bool* tcpGetUsed(void);
|
||||
|
|
|
@ -90,10 +90,10 @@ uint32_t stackUsedSize(void)
|
|||
|
||||
uint32_t stackTotalSize(void)
|
||||
{
|
||||
return (uint32_t)&_Min_Stack_Size;
|
||||
return (uint32_t)(intptr_t)&_Min_Stack_Size;
|
||||
}
|
||||
|
||||
uint32_t stackHighMem(void)
|
||||
{
|
||||
return (uint32_t)&_estack;
|
||||
return (uint32_t)(intptr_t)&_estack;
|
||||
}
|
||||
|
|
|
@ -680,6 +680,9 @@ _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
|
|||
#if USED_TIMERS & TIM_N(12)
|
||||
_TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
|
||||
#endif
|
||||
#if USED_TIMERS & TIM_N(14)
|
||||
_TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler, 14);
|
||||
#endif
|
||||
#if USED_TIMERS & TIM_N(15)
|
||||
_TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
|
||||
#endif
|
||||
|
@ -846,14 +849,14 @@ uint16_t timerDmaSource(uint8_t channel)
|
|||
|
||||
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
||||
{
|
||||
// protection here for desired MHZ > SystemCoreClock???
|
||||
if ((uint32_t)(mhz * 1000000) > (SystemCoreClock / timerClockDivisor(tim))) {
|
||||
// protection here for desired MHZ > timerClock???
|
||||
if ((uint32_t)(mhz * 1000000) > timerClock(tim)) {
|
||||
return 0;
|
||||
}
|
||||
return (uint16_t)(round((SystemCoreClock / timerClockDivisor(tim) / (mhz * 1000000)) - 1));
|
||||
return (uint16_t)(round((timerClock(tim) / (mhz * 1000000)) - 1));
|
||||
}
|
||||
|
||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
|
||||
{
|
||||
return ((uint16_t)((SystemCoreClock / timerClockDivisor(tim) / (prescaler + 1)) / hertz));
|
||||
return ((uint16_t)((timerClock(tim) / (prescaler + 1)) / hertz));
|
||||
}
|
|
@ -181,6 +181,7 @@ void timerStart(void);
|
|||
void timerForceOverflow(TIM_TypeDef *tim);
|
||||
|
||||
uint8_t timerClockDivisor(TIM_TypeDef *tim);
|
||||
uint32_t timerClock(TIM_TypeDef *tim);
|
||||
|
||||
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
|
||||
|
||||
|
|
|
@ -49,3 +49,9 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|||
UNUSED(tim);
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint32_t timerClock(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return SystemCoreClock;
|
||||
}
|
||||
|
|
|
@ -41,3 +41,9 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|||
UNUSED(tim);
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint32_t timerClock(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return SystemCoreClock;
|
||||
}
|
||||
|
|
|
@ -91,3 +91,15 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|||
return 2;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t timerClock(TIM_TypeDef *tim)
|
||||
{
|
||||
#if defined (STM32F40_41xxx)
|
||||
if (tim == TIM8) return SystemCoreClock;
|
||||
#endif
|
||||
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
||||
return SystemCoreClock;
|
||||
} else {
|
||||
return SystemCoreClock / 2;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -80,3 +80,9 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|||
UNUSED(tim);
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint32_t timerClock(TIM_TypeDef *tim)
|
||||
{
|
||||
UNUSED(tim);
|
||||
return SystemCoreClock;
|
||||
}
|
||||
|
|
|
@ -150,7 +150,7 @@ static const char * const featureNames[] = {
|
|||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
|
||||
"UNUSED", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
|
||||
"SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_SENSOR", "ANTI_GRAVITY", NULL
|
||||
"SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_SENSOR", "ANTI_GRAVITY", "DYNAMIC_FILTER", NULL
|
||||
};
|
||||
|
||||
// sync this with rxFailsafeChannelMode_e
|
||||
|
@ -445,7 +445,7 @@ static void cliSetVar(const clivalue_t *var, const cliVar_t value)
|
|||
}
|
||||
}
|
||||
|
||||
#ifndef MINIMAL_CLI
|
||||
#if defined(USE_RESOURCE_MGMT) && !defined(MINIMAL_CLI)
|
||||
static void cliRepeat(char ch, uint8_t len)
|
||||
{
|
||||
for (int i = 0; i < len; i++) {
|
||||
|
|
|
@ -60,6 +60,7 @@ typedef enum {
|
|||
FEATURE_SOFTSPI = 1 << 26,
|
||||
FEATURE_ESC_SENSOR = 1 << 27,
|
||||
FEATURE_ANTI_GRAVITY = 1 << 28,
|
||||
FEATURE_DYNAMIC_FILTER = 1 << 29,
|
||||
} features_e;
|
||||
|
||||
#define MAX_NAME_LENGTH 16
|
||||
|
|
|
@ -133,7 +133,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ BOXLLIGHTS, "LLIGHTS", 16 },
|
||||
{ BOXCALIB, "CALIB", 17 },
|
||||
{ BOXGOV, "GOVERNOR", 18 },
|
||||
{ BOXOSD, "OSD SW", 19 },
|
||||
{ BOXOSD, "OSD DISABLE SW", 19 },
|
||||
{ BOXTELEMETRY, "TELEMETRY", 20 },
|
||||
{ BOXGTUNE, "GTUNE", 21 },
|
||||
{ BOXSONAR, "SONAR", 22 },
|
||||
|
@ -342,7 +342,7 @@ void initActiveBoxIds(void)
|
|||
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
|
||||
}
|
||||
|
||||
if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE) {
|
||||
if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE || mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXPASSTHRU;
|
||||
}
|
||||
|
||||
|
@ -775,6 +775,9 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
|||
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
|
||||
sbufWriteU16(dst, osdConfig()->item_pos[i]);
|
||||
}
|
||||
for (int i = 0; i < OSD_STAT_COUNT; i++ ) {
|
||||
sbufWriteU8(dst, osdConfig()->enabled_stats[i]);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
@ -2039,8 +2042,9 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
case MSP_SET_OSD_CONFIG:
|
||||
{
|
||||
const uint8_t addr = sbufReadU8(src);
|
||||
// set all the other settings
|
||||
|
||||
if ((int8_t)addr == -1) {
|
||||
/* Set general OSD settings */
|
||||
#ifdef USE_MAX7456
|
||||
vcdProfileMutable()->video_system = sbufReadU8(src);
|
||||
#else
|
||||
|
@ -2055,10 +2059,17 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
#endif
|
||||
} else {
|
||||
#if defined(OSD)
|
||||
// set a position setting
|
||||
const uint16_t pos = sbufReadU16(src);
|
||||
if (addr < OSD_ITEM_COUNT) {
|
||||
osdConfigMutable()->item_pos[addr] = pos;
|
||||
const uint16_t value = sbufReadU16(src);
|
||||
|
||||
/* Get screen index, 0 is post flight statsitsics, 1 and above are in flight OSD screens */
|
||||
const uint8_t screen = (sbufBytesRemaining(src) >= 1) ? sbufReadU8(src) : 1;
|
||||
|
||||
if (screen == 0 && addr < OSD_STAT_COUNT) {
|
||||
/* Set statistic item enable */
|
||||
osdConfigMutable()->enabled_stats[addr] = value;
|
||||
} else if (addr < OSD_ITEM_COUNT) {
|
||||
/* Set element positions */
|
||||
osdConfigMutable()->item_pos[addr] = value;
|
||||
}
|
||||
#else
|
||||
return MSP_RESULT_ERROR;
|
||||
|
|
|
@ -75,7 +75,6 @@
|
|||
#include "sensors/battery.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/gyroanalyse.h"
|
||||
#include "sensors/sonar.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
|
||||
|
@ -352,9 +351,6 @@ void fcTasksInit(void)
|
|||
setTaskEnabled(TASK_VTXCTRL, true);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
setTaskEnabled(TASK_GYRO_DATA_ANALYSE, true);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -597,14 +593,5 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
[TASK_GYRO_DATA_ANALYSE] = {
|
||||
.taskName = "GYROFFT",
|
||||
.taskFunc = gyroDataAnalyseUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz, 10ms
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "sensors/esc_sensor.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "fc/settings.h"
|
||||
|
@ -204,7 +205,10 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
|
|||
"STACK",
|
||||
"ESC_SENSOR_RPM",
|
||||
"ESC_SENSOR_TMP",
|
||||
"ALTITUDE"
|
||||
"ALTITUDE",
|
||||
"FFT",
|
||||
"FFT_TIME",
|
||||
"FFT_FREQ"
|
||||
};
|
||||
|
||||
#ifdef OSD
|
||||
|
@ -418,7 +422,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 250 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbathysteresis) },
|
||||
{ "current_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterSource) },
|
||||
{ "battery_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, voltageMeterSource) },
|
||||
{ "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryNotPresentLevel) },
|
||||
{ "vbat_detect_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatnotpresentcellvoltage) },
|
||||
{ "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useVBatAlerts) },
|
||||
{ "use_cbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useConsumptionAlerts) },
|
||||
{ "cbat_alert_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, consumptionWarningPercentage) },
|
||||
|
@ -637,8 +641,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAH_DRAWN]) },
|
||||
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_CRAFT_NAME]) },
|
||||
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_SPEED]) },
|
||||
{ "osd_gps_lon", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_LON]) },
|
||||
{ "osd_gps_lat", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_LAT]) },
|
||||
{ "osd_gps_lon_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_LON]) },
|
||||
{ "osd_gps_lat_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_LAT]) },
|
||||
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_SATS]) },
|
||||
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ALTITUDE]) },
|
||||
{ "osd_pid_roll_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ROLL_PIDS]) },
|
||||
|
@ -653,6 +657,16 @@ const clivalue_t valueTable[] = {
|
|||
{ "osd_rol_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ROLL_ANGLE]) },
|
||||
{ "osd_battery_usage_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_USAGE]) },
|
||||
|
||||
{ "osd_stat_max_spd", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MAX_SPEED])},
|
||||
{ "osd_stat_min_batt", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MIN_BATTERY])},
|
||||
{ "osd_stat_min_rssi", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MIN_RSSI])},
|
||||
{ "osd_stat_max_curr", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MAX_CURRENT])},
|
||||
{ "osd_stat_used_mah", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_USED_MAH])},
|
||||
{ "osd_stat_max_alt", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MAX_ALTITUDE])},
|
||||
{ "osd_stat_bbox", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_BLACKBOX])},
|
||||
{ "osd_stat_endbatt", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_END_BATTERY])},
|
||||
{ "osd_stat_flytime", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_FLYTIME])},
|
||||
{ "osd_stat_armtime", VAR_UINT8 | MASTER_VALUE, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_ARMEDTIME])},
|
||||
#endif
|
||||
|
||||
// PG_SYSTEM_CONFIG
|
||||
|
@ -686,6 +700,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "displayport_max7456_col_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
|
||||
{ "displayport_max7456_row_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
|
||||
#endif
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
{ "esc_sensor_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ESC_SENSOR_CONFIG, offsetof(escSensorConfig_t, halfDuplex) },
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
|
||||
|
|
|
@ -25,8 +25,8 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
@ -38,18 +38,19 @@
|
|||
|
||||
#include "io/motors.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
|
||||
|
||||
|
@ -604,7 +605,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
throttle = 0.5f;
|
||||
}
|
||||
} else {
|
||||
if (isAirmodeActive()) { // Only automatically adjust throttle during airmode scenario
|
||||
if (isAirmodeActive() || throttle > 0.5f) { // Only automatically adjust throttle when airmode enabled. Airmode logic is always active on high throttle
|
||||
const float throttleLimitOffset = motorMixRange / 2.0f;
|
||||
throttle = constrainf(throttle, 0.0f + throttleLimitOffset, 1.0f - throttleLimitOffset);
|
||||
}
|
||||
|
@ -675,10 +676,12 @@ uint16_t convertMotorToExternal(uint16_t motorValue)
|
|||
#ifdef USE_DSHOT
|
||||
if (isMotorProtocolDshot()) {
|
||||
if (feature(FEATURE_3D) && motorValue >= DSHOT_MIN_THROTTLE && motorValue <= DSHOT_3D_DEADBAND_LOW) {
|
||||
motorValue = DSHOT_MIN_THROTTLE + (DSHOT_3D_DEADBAND_LOW - motorValue);
|
||||
// Subtract 1 to compensate for imbalance introduced in convertExternalToMotor()
|
||||
motorValue = DSHOT_MIN_THROTTLE + (DSHOT_3D_DEADBAND_LOW - motorValue) - 1;
|
||||
}
|
||||
|
||||
externalValue = motorValue < DSHOT_MIN_THROTTLE ? EXTERNAL_CONVERSION_MIN_VALUE : constrain((motorValue / EXTERNAL_DSHOT_CONVERSION_FACTOR) + EXTERNAL_DSHOT_CONVERSION_OFFSET, EXTERNAL_CONVERSION_MIN_VALUE + 1, EXTERNAL_CONVERSION_MAX_VALUE);
|
||||
// Subtract 1 to compensate for imbalance introduced in convertExternalToMotor()
|
||||
externalValue = motorValue < DSHOT_MIN_THROTTLE ? EXTERNAL_CONVERSION_MIN_VALUE : constrain(((motorValue - 1)/ EXTERNAL_DSHOT_CONVERSION_FACTOR) + EXTERNAL_DSHOT_CONVERSION_OFFSET, EXTERNAL_CONVERSION_MIN_VALUE + 1, EXTERNAL_CONVERSION_MAX_VALUE);
|
||||
|
||||
if (feature(FEATURE_3D) && motorValue == DSHOT_DISARM_COMMAND) {
|
||||
externalValue = EXTERNAL_CONVERSION_3D_MID_VALUE;
|
||||
|
|
|
@ -158,6 +158,8 @@ static void *ptermYawFilter;
|
|||
|
||||
void pidInitFilters(const pidProfile_t *pidProfile)
|
||||
{
|
||||
BUILD_BUG_ON(FD_YAW != 2); // only setting up Dterm filters on roll and pitch axes, so ensure yaw axis is 2
|
||||
|
||||
static biquadFilter_t biquadFilterNotch[2];
|
||||
static pt1Filter_t pt1Filter[2];
|
||||
static biquadFilter_t biquadFilter[2];
|
||||
|
@ -166,16 +168,25 @@ void pidInitFilters(const pidProfile_t *pidProfile)
|
|||
|
||||
uint32_t pidFrequencyNyquist = (1.0f / dT) / 2; // No rounding needed
|
||||
|
||||
BUILD_BUG_ON(FD_YAW != 2); // only setting up Dterm filters on roll and pitch axes, so ensure yaw axis is 2
|
||||
float dTermNotchHz;
|
||||
if (pidProfile->dterm_notch_hz <= pidFrequencyNyquist) {
|
||||
dTermNotchHz = pidProfile->dterm_notch_hz;
|
||||
} else {
|
||||
if (pidProfile->dterm_notch_cutoff < pidFrequencyNyquist) {
|
||||
dTermNotchHz = pidFrequencyNyquist;
|
||||
} else {
|
||||
dTermNotchHz = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (pidProfile->dterm_notch_hz == 0 || pidProfile->dterm_notch_hz > pidFrequencyNyquist) {
|
||||
if (!dTermNotchHz) {
|
||||
dtermNotchFilterApplyFn = nullFilterApply;
|
||||
} else {
|
||||
dtermNotchFilterApplyFn = (filterApplyFnPtr)biquadFilterApply;
|
||||
const float notchQ = filterGetNotchQ(pidProfile->dterm_notch_hz, pidProfile->dterm_notch_cutoff);
|
||||
const float notchQ = filterGetNotchQ(dTermNotchHz, pidProfile->dterm_notch_cutoff);
|
||||
for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) {
|
||||
dtermFilterNotch[axis] = &biquadFilterNotch[axis];
|
||||
biquadFilterInit(dtermFilterNotch[axis], pidProfile->dterm_notch_hz, targetPidLooptime, notchQ, FILTER_NOTCH);
|
||||
biquadFilterInit(dtermFilterNotch[axis], dTermNotchHz, targetPidLooptime, notchQ, FILTER_NOTCH);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -29,27 +29,27 @@
|
|||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/config_reset.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "io/gimbal.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
extern mixerMode_e currentMixerMode;
|
||||
|
||||
|
@ -92,9 +92,10 @@ void pgResetFn_servoParams(servoParam_t *instance)
|
|||
// no template required since default is zero
|
||||
PG_REGISTER(gimbalConfig_t, gimbalConfig, PG_GIMBAL_CONFIG, 0);
|
||||
|
||||
int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
|
||||
static uint8_t servoRuleCount = 0;
|
||||
static servoMixer_t currentServoMixer[MAX_SERVO_RULES];
|
||||
int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
static int useServo;
|
||||
|
||||
|
||||
|
@ -118,7 +119,7 @@ static const servoMixer_t servoMixerFlyingWing[] = {
|
|||
|
||||
static const servoMixer_t servoMixerBI[] = {
|
||||
{ SERVO_BICOPTER_LEFT, INPUT_STABILIZED_YAW, 100, 0, 0, 100, 0 },
|
||||
{ SERVO_BICOPTER_LEFT, INPUT_STABILIZED_PITCH, 100, 0, 0, 100, 0 },
|
||||
{ SERVO_BICOPTER_LEFT, INPUT_STABILIZED_PITCH, -100, 0, 0, 100, 0 },
|
||||
{ SERVO_BICOPTER_RIGHT, INPUT_STABILIZED_YAW, 100, 0, 0, 100, 0 },
|
||||
{ SERVO_BICOPTER_RIGHT, INPUT_STABILIZED_PITCH, 100, 0, 0, 100, 0 },
|
||||
};
|
||||
|
@ -226,7 +227,7 @@ void loadCustomServoMixer(void)
|
|||
memset(currentServoMixer, 0, sizeof(currentServoMixer));
|
||||
|
||||
// load custom mixer into currentServoMixer
|
||||
for (uint8_t i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
// check if done
|
||||
if (customServoMixers(i)->rate == 0)
|
||||
break;
|
||||
|
@ -368,7 +369,6 @@ STATIC_UNIT_TESTED void servoMixer(void)
|
|||
{
|
||||
int16_t input[INPUT_SOURCE_COUNT]; // Range [-500:+500]
|
||||
static int16_t currentOutput[MAX_SERVO_RULES];
|
||||
uint8_t i;
|
||||
|
||||
if (FLIGHT_MODE(PASSTHRU_MODE)) {
|
||||
// Direct passthru from RX
|
||||
|
@ -407,11 +407,12 @@ STATIC_UNIT_TESTED void servoMixer(void)
|
|||
input[INPUT_RC_AUX3] = rcData[AUX3] - rxConfig()->midrc;
|
||||
input[INPUT_RC_AUX4] = rcData[AUX4] - rxConfig()->midrc;
|
||||
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++)
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servo[i] = 0;
|
||||
}
|
||||
|
||||
// mix servos according to rules
|
||||
for (i = 0; i < servoRuleCount; i++) {
|
||||
for (int i = 0; i < servoRuleCount; i++) {
|
||||
// consider rule if no box assigned or box is active
|
||||
if (currentServoMixer[i].box == 0 || IS_RC_MODE_ACTIVE(BOXSERVO1 + currentServoMixer[i].box - 1)) {
|
||||
uint8_t target = currentServoMixer[i].targetChannel;
|
||||
|
@ -435,7 +436,7 @@ STATIC_UNIT_TESTED void servoMixer(void)
|
|||
}
|
||||
}
|
||||
|
||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servo[i] = ((int32_t)servoParams(i)->rate * servo[i]) / 100L;
|
||||
servo[i] += determineServoMiddleOrForwardFromChannel(i);
|
||||
}
|
||||
|
|
|
@ -152,7 +152,11 @@ static const uint8_t ubloxInit[] = {
|
|||
// 31.21 CFG-SBAS (0x06 0x16), Page 142/210
|
||||
// A.10 SBAS Configuration (UBX-CFG-SBAS), Page 198/210 - GPS.G6-SW-10018-F
|
||||
|
||||
#define UBLOX_SBAS_MESSAGE_LENGTH 16
|
||||
#define UBLOX_SBAS_PREFIX_LENGTH 10
|
||||
|
||||
static const uint8_t ubloxSbasPrefix[UBLOX_SBAS_PREFIX_LENGTH] = { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00 };
|
||||
|
||||
#define UBLOX_SBAS_MESSAGE_LENGTH 6
|
||||
typedef struct ubloxSbas_s {
|
||||
sbasMode_e mode;
|
||||
uint8_t message[UBLOX_SBAS_MESSAGE_LENGTH];
|
||||
|
@ -163,11 +167,11 @@ typedef struct ubloxSbas_s {
|
|||
// Note: these must be defined in the same order is sbasMode_e since no lookup table is used.
|
||||
static const ubloxSbas_t ubloxSbas[] = {
|
||||
// NOTE this could be optimized to save a few bytes of flash space since the same prefix is used for each command.
|
||||
{ SBAS_AUTO, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x31, 0xE5}},
|
||||
{ SBAS_EGNOS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41}},
|
||||
{ SBAS_WAAS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x04, 0xE0, 0x04, 0x00, 0x19, 0x9D}},
|
||||
{ SBAS_MSAS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x00, 0x02, 0x02, 0x00, 0x35, 0xEF}},
|
||||
{ SBAS_GAGAN, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x80, 0x01, 0x00, 0x00, 0xB2, 0xE8}}
|
||||
{ SBAS_AUTO, { 0x00, 0x00, 0x00, 0x00, 0x31, 0xE5}},
|
||||
{ SBAS_EGNOS, { 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41}},
|
||||
{ SBAS_WAAS, { 0x04, 0xE0, 0x04, 0x00, 0x19, 0x9D}},
|
||||
{ SBAS_MSAS, { 0x00, 0x02, 0x02, 0x00, 0x35, 0xEF}},
|
||||
{ SBAS_GAGAN, { 0x80, 0x01, 0x00, 0x00, 0xB2, 0xE8}}
|
||||
};
|
||||
|
||||
|
||||
|
@ -372,8 +376,11 @@ void gpsInitUblox(void)
|
|||
}
|
||||
|
||||
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
|
||||
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) {
|
||||
serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position]);
|
||||
if (gpsData.state_position < UBLOX_SBAS_PREFIX_LENGTH) {
|
||||
serialWrite(gpsPort, ubloxSbasPrefix[gpsData.state_position]);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < UBLOX_SBAS_PREFIX_LENGTH + UBLOX_SBAS_MESSAGE_LENGTH) {
|
||||
serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position - UBLOX_SBAS_PREFIX_LENGTH]);
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
gpsData.messageState++;
|
||||
|
|
|
@ -120,6 +120,7 @@ typedef struct statistic_s {
|
|||
int16_t max_current; // /10
|
||||
int16_t min_rssi;
|
||||
int16_t max_altitude;
|
||||
uint16_t armed_time;
|
||||
} statistic_t;
|
||||
|
||||
static statistic_t stats;
|
||||
|
@ -274,6 +275,13 @@ static void osdDrawSingleElement(uint8_t item)
|
|||
break;
|
||||
}
|
||||
|
||||
case OSD_ARMED_TIME:
|
||||
{
|
||||
buff[0] = SYM_FLY_M;
|
||||
tfp_sprintf(buff + 1, "%02d:%02d", stats.armed_time / 60, stats.armed_time % 60);
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_FLYMODE:
|
||||
{
|
||||
char *p = "ACRO";
|
||||
|
@ -564,6 +572,7 @@ void osdDrawElements(void)
|
|||
osdDrawSingleElement(OSD_PITCH_ANGLE);
|
||||
osdDrawSingleElement(OSD_ROLL_ANGLE);
|
||||
osdDrawSingleElement(OSD_MAIN_BATT_USAGE);
|
||||
osdDrawSingleElement(OSD_ARMED_TIME);
|
||||
|
||||
#ifdef GPS
|
||||
#ifdef CMS
|
||||
|
@ -608,13 +617,23 @@ void pgResetFn_osdConfig(osdConfig_t *osdProfile)
|
|||
osdProfile->item_pos[OSD_DEBUG] = OSD_POS(7, 12) | VISIBLE_FLAG;
|
||||
osdProfile->item_pos[OSD_PITCH_ANGLE] = OSD_POS(1, 8) | VISIBLE_FLAG;
|
||||
osdProfile->item_pos[OSD_ROLL_ANGLE] = OSD_POS(1, 9) | VISIBLE_FLAG;
|
||||
|
||||
osdProfile->item_pos[OSD_GPS_LAT] = OSD_POS(18, 14) | VISIBLE_FLAG;
|
||||
osdProfile->item_pos[OSD_GPS_LON] = OSD_POS(18, 15) | VISIBLE_FLAG;
|
||||
osdProfile->item_pos[OSD_MAIN_BATT_USAGE] = OSD_POS(15, 10) | VISIBLE_FLAG;
|
||||
|
||||
osdProfile->enabled_stats[OSD_STAT_MAX_SPEED] = true;
|
||||
osdProfile->enabled_stats[OSD_STAT_MIN_BATTERY] = true;
|
||||
osdProfile->enabled_stats[OSD_STAT_MIN_RSSI] = true;
|
||||
osdProfile->enabled_stats[OSD_STAT_MAX_CURRENT] = true;
|
||||
osdProfile->enabled_stats[OSD_STAT_USED_MAH] = true;
|
||||
osdProfile->enabled_stats[OSD_STAT_MAX_ALTITUDE] = false;
|
||||
osdProfile->enabled_stats[OSD_STAT_BLACKBOX] = true;
|
||||
osdProfile->enabled_stats[OSD_STAT_END_BATTERY] = false;
|
||||
osdProfile->enabled_stats[OSD_STAT_FLYTIME] = false;
|
||||
osdProfile->enabled_stats[OSD_STAT_ARMEDTIME] = true;
|
||||
|
||||
osdProfile->units = OSD_UNIT_METRIC;
|
||||
|
||||
osdProfile->rssi_alarm = 20;
|
||||
osdProfile->cap_alarm = 2200;
|
||||
osdProfile->time_alarm = 10; // in minutes
|
||||
|
@ -736,6 +755,7 @@ static void osdResetStats(void)
|
|||
stats.max_current = 0;
|
||||
stats.min_rssi = 99;
|
||||
stats.max_altitude = 0;
|
||||
stats.armed_time = 0;
|
||||
}
|
||||
|
||||
static void osdUpdateStats(void)
|
||||
|
@ -804,6 +824,13 @@ static void osdGetBlackboxStatusString(char * buff, uint8_t len)
|
|||
}
|
||||
#endif
|
||||
|
||||
static void osdDisplayStatisticLabel(uint8_t y, const char * text, const char * value)
|
||||
{
|
||||
displayWrite(osdDisplayPort, 2, y, text);
|
||||
displayWrite(osdDisplayPort, 20, y, ":");
|
||||
displayWrite(osdDisplayPort, 22, y, value);
|
||||
}
|
||||
|
||||
static void osdShowStats(void)
|
||||
{
|
||||
uint8_t top = 2;
|
||||
|
@ -812,43 +839,60 @@ static void osdShowStats(void)
|
|||
displayClearScreen(osdDisplayPort);
|
||||
displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
|
||||
|
||||
if (STATE(GPS_FIX)) {
|
||||
displayWrite(osdDisplayPort, 2, top, "MAX SPEED :");
|
||||
itoa(stats.max_speed, buff, 10);
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_ARMEDTIME]) {
|
||||
tfp_sprintf(buff, "%02d:%02d", stats.armed_time / 60, stats.armed_time % 60);
|
||||
osdDisplayStatisticLabel(top++, "ARMED TIME", buff);
|
||||
}
|
||||
|
||||
displayWrite(osdDisplayPort, 2, top, "MIN BATTERY :");
|
||||
tfp_sprintf(buff, "%d.%1dV", stats.min_voltage / 10, stats.min_voltage % 10);
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_FLYTIME]) {
|
||||
tfp_sprintf(buff, "%02d:%02d", flyTime / 60, flyTime % 60);
|
||||
osdDisplayStatisticLabel(top++, "FLY TIME", buff);
|
||||
}
|
||||
|
||||
displayWrite(osdDisplayPort, 2, top, "MIN RSSI :");
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_MAX_SPEED] && STATE(GPS_FIX)) {
|
||||
itoa(stats.max_speed, buff, 10);
|
||||
osdDisplayStatisticLabel(top++, "MAX SPEED", buff);
|
||||
}
|
||||
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_MIN_BATTERY]) {
|
||||
tfp_sprintf(buff, "%d.%1dV", stats.min_voltage / 10, stats.min_voltage % 10);
|
||||
osdDisplayStatisticLabel(top++, "MIN BATTERY", buff);
|
||||
}
|
||||
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_END_BATTERY]) {
|
||||
tfp_sprintf(buff, "%d.%1dV", getBatteryVoltage() / 10, getBatteryVoltage() % 10);
|
||||
osdDisplayStatisticLabel(top++, "END BATTERY", buff);
|
||||
}
|
||||
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_MIN_RSSI]) {
|
||||
itoa(stats.min_rssi, buff, 10);
|
||||
strcat(buff, "%");
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
|
||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||
displayWrite(osdDisplayPort, 2, top, "MAX CURRENT :");
|
||||
itoa(stats.max_current, buff, 10);
|
||||
strcat(buff, "A");
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
|
||||
displayWrite(osdDisplayPort, 2, top, "USED MAH :");
|
||||
itoa(getMAhDrawn(), buff, 10);
|
||||
strcat(buff, "\x07");
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
osdDisplayStatisticLabel(top++, "MIN RSSI", buff);
|
||||
}
|
||||
|
||||
displayWrite(osdDisplayPort, 2, top, "MAX ALTITUDE :");
|
||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_MAX_CURRENT]) {
|
||||
itoa(stats.max_current, buff, 10);
|
||||
strcat(buff, "A");
|
||||
osdDisplayStatisticLabel(top++, "MAX CURRENT", buff);
|
||||
}
|
||||
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_USED_MAH]) {
|
||||
tfp_sprintf(buff, "%d%c", getMAhDrawn(), SYM_MAH);
|
||||
osdDisplayStatisticLabel(top++, "USED MAH", buff);
|
||||
}
|
||||
}
|
||||
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_MAX_ALTITUDE]) {
|
||||
int32_t alt = osdGetAltitude(stats.max_altitude);
|
||||
tfp_sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
osdDisplayStatisticLabel(top++, "MAX ALTITUDE", buff);
|
||||
}
|
||||
|
||||
#ifdef BLACKBOX
|
||||
if (blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) {
|
||||
displayWrite(osdDisplayPort, 2, top, "BLACKBOX :");
|
||||
if (osdConfig()->enabled_stats[OSD_STAT_BLACKBOX] && blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) {
|
||||
osdGetBlackboxStatusString(buff, 10);
|
||||
displayWrite(osdDisplayPort, 22, top++, buff);
|
||||
osdDisplayStatisticLabel(top++, "BLACKBOX", buff);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -884,6 +928,7 @@ static void osdRefresh(timeUs_t currentTimeUs)
|
|||
|
||||
if (ARMING_FLAG(ARMED) && sec != lastSec) {
|
||||
flyTime++;
|
||||
stats.armed_time++;
|
||||
lastSec = sec;
|
||||
}
|
||||
|
||||
|
|
|
@ -56,9 +56,24 @@ typedef enum {
|
|||
OSD_PITCH_ANGLE,
|
||||
OSD_ROLL_ANGLE,
|
||||
OSD_MAIN_BATT_USAGE,
|
||||
OSD_ARMED_TIME,
|
||||
OSD_ITEM_COUNT // MUST BE LAST
|
||||
} osd_items_e;
|
||||
|
||||
typedef enum {
|
||||
OSD_STAT_MAX_SPEED,
|
||||
OSD_STAT_MIN_BATTERY,
|
||||
OSD_STAT_MIN_RSSI,
|
||||
OSD_STAT_MAX_CURRENT,
|
||||
OSD_STAT_USED_MAH,
|
||||
OSD_STAT_MAX_ALTITUDE,
|
||||
OSD_STAT_BLACKBOX,
|
||||
OSD_STAT_END_BATTERY,
|
||||
OSD_STAT_FLYTIME,
|
||||
OSD_STAT_ARMEDTIME,
|
||||
OSD_STAT_COUNT // MUST BE LAST
|
||||
} osd_states_e;
|
||||
|
||||
typedef enum {
|
||||
OSD_UNIT_IMPERIAL,
|
||||
OSD_UNIT_METRIC
|
||||
|
@ -66,6 +81,7 @@ typedef enum {
|
|||
|
||||
typedef struct osdConfig_s {
|
||||
uint16_t item_pos[OSD_ITEM_COUNT];
|
||||
bool enabled_stats[OSD_STAT_COUNT];
|
||||
|
||||
// Alarms
|
||||
uint8_t rssi_alarm;
|
||||
|
|
|
@ -39,6 +39,10 @@
|
|||
|
||||
#define USE_SERIAL (defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||
|
||||
#ifdef SITL
|
||||
#include "drivers/serial_tcp.h"
|
||||
#endif
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#if defined(USE_VCP)
|
||||
|
@ -374,7 +378,12 @@ serialPort_t *openSerialPort(
|
|||
#ifdef USE_UART8
|
||||
case SERIAL_PORT_USART8:
|
||||
#endif
|
||||
#ifdef SITL
|
||||
// SITL emulates serial ports over TCP
|
||||
serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
|
||||
#else
|
||||
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -110,9 +110,6 @@ typedef enum {
|
|||
#ifdef VTX_CONTROL
|
||||
TASK_VTXCTRL,
|
||||
#endif
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
TASK_GYRO_DATA_ANALYSE,
|
||||
#endif
|
||||
|
||||
/* Count of real tasks */
|
||||
TASK_COUNT,
|
||||
|
|
|
@ -27,9 +27,10 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "config/config_reset.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_adxl345.h"
|
||||
|
@ -61,8 +62,6 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
|
|
@ -70,6 +70,10 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
|||
|
||||
baroSensor_e baroHardware = baroHardwareToUse;
|
||||
|
||||
#if !defined(USE_BARO_BMP085) && !defined(USE_BARO_MS5611) && !defined(USE_BARO_BMP280) && !defined(USE_BARO_SPI_BMP280)
|
||||
UNUSED(dev);
|
||||
#endif
|
||||
|
||||
#ifdef USE_BARO_BMP085
|
||||
const bmp085Config_t *bmp085Config = NULL;
|
||||
|
||||
|
|
|
@ -70,9 +70,7 @@ static batteryState_e batteryState;
|
|||
static batteryState_e voltageState;
|
||||
static batteryState_e consumptionState;
|
||||
|
||||
#ifdef BOARD_HAS_CURRENT_SENSOR
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#else
|
||||
#ifndef DEFAULT_CURRENT_METER_SOURCE
|
||||
#ifdef USE_VIRTUAL_CURRENT_METER
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_VIRTUAL
|
||||
#else
|
||||
|
@ -84,9 +82,7 @@ static batteryState_e consumptionState;
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#else
|
||||
#ifndef DEFAULT_VOLTAGE_METER_SOURCE
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_NONE
|
||||
#endif
|
||||
|
||||
|
@ -97,12 +93,12 @@ PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
|
|||
.vbatmaxcellvoltage = 43,
|
||||
.vbatmincellvoltage = 33,
|
||||
.vbatwarningcellvoltage = 35,
|
||||
.batteryNotPresentLevel = 55, // VBAT below 5.5 V will be ignored
|
||||
.vbatnotpresentcellvoltage = 30, //A cell below 3 will be ignored
|
||||
.voltageMeterSource = DEFAULT_VOLTAGE_METER_SOURCE,
|
||||
|
||||
// current
|
||||
.batteryCapacity = 0,
|
||||
.currentMeterSource = DEFAULT_VOLTAGE_METER_SOURCE,
|
||||
.currentMeterSource = DEFAULT_CURRENT_METER_SOURCE,
|
||||
|
||||
// warnings / alerts
|
||||
.useVBatAlerts = true,
|
||||
|
@ -162,16 +158,19 @@ void batteryUpdatePresence(void)
|
|||
{
|
||||
static uint16_t previousVoltage = 0;
|
||||
|
||||
bool isVoltageStable = (
|
||||
previousVoltage > 0
|
||||
&& ABS(voltageMeter.filtered - previousVoltage) <= VBAT_STABLE_MAX_DELTA
|
||||
);
|
||||
bool isVoltageStable = ABS(voltageMeter.filtered - previousVoltage) <= VBAT_STABLE_MAX_DELTA;
|
||||
|
||||
bool isVoltageFromBat = (voltageMeter.filtered >= batteryConfig()->vbatnotpresentcellvoltage //above ~0V
|
||||
&& voltageMeter.filtered <= batteryConfig()->vbatmaxcellvoltage) //1s max cell voltage check
|
||||
|| voltageMeter.filtered > batteryConfig()->vbatnotpresentcellvoltage*2; //USB voltage - 2s or more check
|
||||
|
||||
|
||||
if (
|
||||
voltageState == BATTERY_NOT_PRESENT
|
||||
&& voltageMeter.filtered > batteryConfig()->batteryNotPresentLevel
|
||||
&& isVoltageFromBat
|
||||
&& isVoltageStable
|
||||
) {
|
||||
/* Want to disable battery getting detected around USB voltage or 0V*/
|
||||
/* battery has just been connected - calculate cells, warning voltages and reset state */
|
||||
|
||||
|
||||
|
@ -187,10 +186,10 @@ void batteryUpdatePresence(void)
|
|||
batteryCriticalVoltage = batteryCellCount * batteryConfig()->vbatmincellvoltage;
|
||||
} else if (
|
||||
voltageState != BATTERY_NOT_PRESENT
|
||||
&& voltageMeter.filtered <= batteryConfig()->batteryNotPresentLevel
|
||||
&& isVoltageStable
|
||||
&& !isVoltageFromBat
|
||||
) {
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of batteryConfig()->batterynotpresentlevel */
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of batteryConfig()->vbatnotpresentcellvoltage */
|
||||
|
||||
consumptionState = voltageState = BATTERY_NOT_PRESENT;
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@ typedef struct batteryConfig_s {
|
|||
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
|
||||
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery critical alarm, in 0.1V units, default is 33 (3.3V)
|
||||
uint8_t vbatwarningcellvoltage; // warning voltage per cell, this triggers battery warning alarm, in 0.1V units, default is 35 (3.5V)
|
||||
uint8_t batteryNotPresentLevel; // Below this level battery is considered as not present
|
||||
uint8_t vbatnotpresentcellvoltage; // Between vbatmaxcellvoltage and 2*this is considered to be USB powered. Below this it is notpresent
|
||||
|
||||
voltageMeterSource_e voltageMeterSource; // source of battery voltage meter used, either ADC or ESC
|
||||
|
||||
|
|
|
@ -64,6 +64,12 @@ Byte 9: 8-bit CRC
|
|||
|
||||
*/
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(escSensorConfig_t, escSensorConfig, PG_ESC_SENSOR_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(escSensorConfig_t, escSensorConfig,
|
||||
.halfDuplex = 0
|
||||
);
|
||||
|
||||
/*
|
||||
DEBUG INFORMATION
|
||||
-----------------
|
||||
|
@ -183,7 +189,7 @@ bool escSensorInit(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
portOptions_t options = (SERIAL_NOT_INVERTED);
|
||||
portOptions_t options = SERIAL_NOT_INVERTED | (escSensorConfig()->halfDuplex ? SERIAL_BIDIR : 0);
|
||||
|
||||
// Initialize serial port
|
||||
escSensorPort = openSerialPort(portConfig->identifier, FUNCTION_ESC_SENSOR, escSensorDataReceive, ESC_SENSOR_BAUDRATE, MODE_RX, options);
|
||||
|
|
|
@ -19,6 +19,12 @@
|
|||
|
||||
#include "common/time.h"
|
||||
|
||||
typedef struct escSensorConfig_s {
|
||||
uint8_t halfDuplex; // Set to false to listen on the TX pin for telemetry data
|
||||
} escSensorConfig_t;
|
||||
|
||||
PG_DECLARE(escSensorConfig_t, escSensorConfig);
|
||||
|
||||
typedef struct {
|
||||
uint8_t dataAge;
|
||||
int8_t temperature;
|
||||
|
|
|
@ -96,6 +96,8 @@ typedef struct gyroSensor_s {
|
|||
biquadFilter_t notchFilter1[XYZ_AXIS_COUNT];
|
||||
filterApplyFnPtr notchFilter2ApplyFn;
|
||||
biquadFilter_t notchFilter2[XYZ_AXIS_COUNT];
|
||||
filterApplyFnPtr notchFilterDynApplyFn;
|
||||
biquadFilter_t notchFilterDyn[XYZ_AXIS_COUNT];
|
||||
} gyroSensor_t;
|
||||
|
||||
static gyroSensor_t gyroSensor0;
|
||||
|
@ -362,7 +364,7 @@ bool gyroInit(void)
|
|||
void gyroInitFilterLpf(gyroSensor_t *gyroSensor, uint8_t lpfHz)
|
||||
{
|
||||
gyroSensor->softLpfFilterApplyFn = nullFilterApply;
|
||||
const uint32_t gyroFrequencyNyquist = (1.0f / (gyro.targetLooptime * 0.000001f)) / 2; // No rounding needed
|
||||
const uint32_t gyroFrequencyNyquist = 1000000 / 2 / gyro.targetLooptime;
|
||||
|
||||
if (lpfHz && lpfHz <= gyroFrequencyNyquist) { // Initialisation needs to happen once samplingrate is known
|
||||
switch (gyroConfig()->gyro_soft_lpf_type) {
|
||||
|
@ -392,11 +394,27 @@ void gyroInitFilterLpf(gyroSensor_t *gyroSensor, uint8_t lpfHz)
|
|||
}
|
||||
}
|
||||
|
||||
static uint16_t calculateNyquistAdjustedNotchHz(uint16_t notchHz, uint16_t notchCutoffHz)
|
||||
{
|
||||
const uint32_t gyroFrequencyNyquist = 1000000 / 2 / gyro.targetLooptime;
|
||||
if (notchHz > gyroFrequencyNyquist) {
|
||||
if (notchCutoffHz < gyroFrequencyNyquist) {
|
||||
notchHz = gyroFrequencyNyquist;
|
||||
} else {
|
||||
notchHz = 0;
|
||||
}
|
||||
}
|
||||
|
||||
return notchHz;
|
||||
}
|
||||
|
||||
void gyroInitFilterNotch1(gyroSensor_t *gyroSensor, uint16_t notchHz, uint16_t notchCutoffHz)
|
||||
{
|
||||
gyroSensor->notchFilter1ApplyFn = nullFilterApply;
|
||||
const uint32_t gyroFrequencyNyquist = (1.0f / (gyro.targetLooptime * 0.000001f)) / 2; // No rounding needed
|
||||
if (notchHz && notchHz <= gyroFrequencyNyquist) {
|
||||
|
||||
notchHz = calculateNyquistAdjustedNotchHz(notchHz, notchCutoffHz);
|
||||
|
||||
if (notchHz) {
|
||||
gyroSensor->notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply;
|
||||
const float notchQ = filterGetNotchQ(notchHz, notchCutoffHz);
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
|
@ -407,10 +425,11 @@ void gyroInitFilterNotch1(gyroSensor_t *gyroSensor, uint16_t notchHz, uint16_t n
|
|||
|
||||
void gyroInitFilterNotch2(gyroSensor_t *gyroSensor, uint16_t notchHz, uint16_t notchCutoffHz)
|
||||
{
|
||||
|
||||
gyroSensor->notchFilter2ApplyFn = nullFilterApply;
|
||||
const uint32_t gyroFrequencyNyquist = (1.0f / (gyro.targetLooptime * 0.000001f)) / 2; // No rounding needed
|
||||
if (notchHz && notchHz <= gyroFrequencyNyquist) {
|
||||
|
||||
notchHz = calculateNyquistAdjustedNotchHz(notchHz, notchCutoffHz);
|
||||
|
||||
if (notchHz) {
|
||||
gyroSensor->notchFilter2ApplyFn = (filterApplyFnPtr)biquadFilterApply;
|
||||
const float notchQ = filterGetNotchQ(notchHz, notchCutoffHz);
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
|
@ -419,11 +438,21 @@ void gyroInitFilterNotch2(gyroSensor_t *gyroSensor, uint16_t notchHz, uint16_t n
|
|||
}
|
||||
}
|
||||
|
||||
void gyroInitFilterDynamicNotch(gyroSensor_t *gyroSensor)
|
||||
{
|
||||
gyroSensor->notchFilterDynApplyFn = (filterApplyFnPtr)biquadFilterApplyDF1; // must be this function, not DF2
|
||||
const float notchQ = filterGetNotchQ(400, 390); //just any init value
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
biquadFilterInit(&gyroSensor->notchFilterDyn[axis], 400, gyro.targetLooptime, notchQ, FILTER_NOTCH);
|
||||
}
|
||||
}
|
||||
|
||||
static void gyroInitSensorFilters(gyroSensor_t *gyroSensor)
|
||||
{
|
||||
gyroInitFilterLpf(gyroSensor, gyroConfig()->gyro_soft_lpf_hz);
|
||||
gyroInitFilterNotch1(gyroSensor, gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1);
|
||||
gyroInitFilterNotch2(gyroSensor, gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2);
|
||||
gyroInitFilterDynamicNotch(gyroSensor);
|
||||
}
|
||||
|
||||
void gyroInitFilters(void)
|
||||
|
@ -506,6 +535,7 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t
|
|||
void gyroUpdateSensor(gyroSensor_t *gyroSensor)
|
||||
{
|
||||
if (!gyroSensor->gyroDev.readFn(&gyroSensor->gyroDev)) {
|
||||
|
||||
return;
|
||||
}
|
||||
gyroSensor->gyroDev.dataReady = false;
|
||||
|
@ -527,24 +557,37 @@ void gyroUpdateSensor(gyroSensor_t *gyroSensor)
|
|||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
gyroDataAnalyse(&gyroSensor->gyroDev, gyroSensor->notchFilterDyn);
|
||||
#endif
|
||||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
// scale gyro output to degrees per second
|
||||
float gyroADCf = (float)gyroSensor->gyroDev.gyroADC[axis] * gyroSensor->gyroDev.scale;
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
// Apply Dynamic Notch filtering
|
||||
if (axis == 0)
|
||||
DEBUG_SET(DEBUG_FFT, 0, lrintf(gyroADCf)); // store raw data
|
||||
|
||||
if (isDynamicFilterActive())
|
||||
gyroADCf = gyroSensor->notchFilterDynApplyFn(&gyroSensor->notchFilterDyn[axis], gyroADCf);
|
||||
|
||||
if (axis == 0)
|
||||
DEBUG_SET(DEBUG_FFT, 1, lrintf(gyroADCf)); // store data after dynamic notch
|
||||
#endif
|
||||
|
||||
// Apply Static Notch filtering
|
||||
DEBUG_SET(DEBUG_NOTCH, axis, lrintf(gyroADCf));
|
||||
gyroADCf = gyroSensor->notchFilter1ApplyFn(&gyroSensor->notchFilter1[axis], gyroADCf);
|
||||
gyroADCf = gyroSensor->notchFilter2ApplyFn(&gyroSensor->notchFilter2[axis], gyroADCf);
|
||||
|
||||
// Apply LPF
|
||||
DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf));
|
||||
gyroADCf = gyroSensor->softLpfFilterApplyFn(gyroSensor->softLpfFilterPtr[axis], gyroADCf);
|
||||
|
||||
// Apply Notch filtering
|
||||
DEBUG_SET(DEBUG_NOTCH, axis, lrintf(gyroADCf));
|
||||
gyroADCf = gyroSensor->notchFilter1ApplyFn(&gyroSensor->notchFilter1[axis], gyroADCf);
|
||||
gyroADCf = gyroSensor->notchFilter2ApplyFn(&gyroSensor->notchFilter2[axis], gyroADCf);
|
||||
gyro.gyroADCf[axis] = gyroADCf;
|
||||
}
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
gyroDataAnalyse(&gyroSensor->gyroDev, &gyro);
|
||||
#endif
|
||||
}
|
||||
|
||||
void gyroUpdate(void)
|
||||
|
|
|
@ -17,9 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "common/axis.h"
|
||||
#include "drivers/io_types.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
typedef enum {
|
||||
|
@ -66,6 +65,7 @@ typedef struct gyroConfig_s {
|
|||
PG_DECLARE(gyroConfig_t, gyroConfig);
|
||||
|
||||
bool gyroInit(void);
|
||||
|
||||
void gyroInitFilters(void);
|
||||
void gyroUpdate(void);
|
||||
const busDevice_t *gyroSensorBus(void);
|
||||
|
|
|
@ -1,35 +1,323 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
|
||||
#include "arm_math.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/time.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/gyroanalyse.h"
|
||||
|
||||
#include "common/filter.h"
|
||||
|
||||
void gyroDataAnalyseInit(void)
|
||||
// The FFT splits the frequency domain into an number of bins
|
||||
// A sampling frequency of 1000 and max frequency of 500 at a window size of 32 gives 16 frequency bins each with a width 31.25Hz
|
||||
// Eg [0,31), [31,62), [62, 93) etc
|
||||
|
||||
#define FFT_WINDOW_SIZE 32 // max for f3 targets
|
||||
#define FFT_MIN_FREQ 100 // not interested in filtering frequencies below 100Hz
|
||||
#define FFT_SAMPLING_RATE 1000 // allows analysis up to 500Hz which is more than motors create
|
||||
#define FFT_BPF_HZ 200 // use a bandpass on gyro data to ignore extreme low and extreme high frequencies
|
||||
#define DYN_NOTCH_WIDTH 100 // just an orientation and start value
|
||||
#define DYN_NOTCH_CHANGERATE 60 // lower cut does not improve the performance much, higher cut makes it worse...
|
||||
#define DYN_NOTCH_MIN_CUTOFF 120 // don't cut too deep into low frequencies
|
||||
#define DYN_NOTCH_MAX_CUTOFF 200 // don't go above this cutoff (better filtering with "constant" delay at higher center frequencies)
|
||||
|
||||
#define BIQUAD_Q 1.0f / sqrtf(2.0f) // quality factor - butterworth
|
||||
|
||||
static uint16_t samplingFrequency; // gyro rate
|
||||
static uint8_t fftBinCount;
|
||||
static float fftResolution; // hz per bin
|
||||
static float gyroData[3][FFT_WINDOW_SIZE]; // gyro data used for frequency analysis
|
||||
|
||||
static arm_rfft_fast_instance_f32 fftInstance;
|
||||
static float fftData[FFT_WINDOW_SIZE];
|
||||
static float rfftData[FFT_WINDOW_SIZE];
|
||||
static gyroFftData_t fftResult[3];
|
||||
static uint16_t fftMaxFreq = 0; // nyquist rate
|
||||
static uint16_t fftIdx = 0; // use a circular buffer for the last FFT_WINDOW_SIZE samples
|
||||
|
||||
|
||||
// accumulator for oversampled data => no aliasing and less noise
|
||||
static float fftAcc[3] = {0, 0, 0};
|
||||
static int fftAccCount = 0;
|
||||
static int fftSamplingScale;
|
||||
|
||||
// bandpass filter gyro data
|
||||
static biquadFilter_t fftGyroFilter[3];
|
||||
|
||||
// filter for smoothing frequency estimation
|
||||
static biquadFilter_t fftFreqFilter[3];
|
||||
|
||||
// Hanning window, see https://en.wikipedia.org/wiki/Window_function#Hann_.28Hanning.29_window
|
||||
static float hanningWindow[FFT_WINDOW_SIZE];
|
||||
|
||||
void initHanning()
|
||||
{
|
||||
for (int i = 0; i < FFT_WINDOW_SIZE; i++) {
|
||||
hanningWindow[i] = (0.5 - 0.5 * cosf(2 * M_PIf * i / (FFT_WINDOW_SIZE - 1)));
|
||||
}
|
||||
}
|
||||
|
||||
void gyroDataAnalyse(const gyroDev_t *gyroDev, const gyro_t *gyro)
|
||||
void initGyroData()
|
||||
{
|
||||
UNUSED(gyroDev);
|
||||
UNUSED(gyro);
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
for (int i = 0; i < FFT_WINDOW_SIZE; i++) {
|
||||
gyroData[axis][i] = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void gyroDataAnalyseUpdate(timeUs_t currentTimeUs)
|
||||
static inline int fftFreqToBin(int freq)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
return ((FFT_WINDOW_SIZE / 2 - 1) * freq) / (fftMaxFreq);
|
||||
}
|
||||
|
||||
void gyroDataAnalyseInit(uint32_t targetLooptimeUs)
|
||||
{
|
||||
// initialise even if FEATURE_DYNAMIC_FILTER not set, since it may be set later
|
||||
samplingFrequency = 1000000 / targetLooptimeUs;
|
||||
fftSamplingScale = samplingFrequency / FFT_SAMPLING_RATE;
|
||||
fftMaxFreq = FFT_SAMPLING_RATE / 2;
|
||||
fftBinCount = fftFreqToBin(fftMaxFreq) + 1;
|
||||
fftResolution = FFT_SAMPLING_RATE / FFT_WINDOW_SIZE;
|
||||
arm_rfft_fast_init_f32(&fftInstance, FFT_WINDOW_SIZE);
|
||||
|
||||
initGyroData();
|
||||
initHanning();
|
||||
|
||||
// recalculation of filters takes 4 calls per axis => each filter gets updated every 3 * 4 = 12 calls
|
||||
// at 4khz gyro loop rate this means 4khz / 4 / 3 = 333Hz => update every 3ms
|
||||
float looptime = targetLooptimeUs * 4 * 3;
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
fftResult[axis].centerFreq = 200; // any init value
|
||||
biquadFilterInitLPF(&fftFreqFilter[axis], DYN_NOTCH_CHANGERATE, looptime);
|
||||
biquadFilterInit(&fftGyroFilter[axis], FFT_BPF_HZ, 1000000 / FFT_SAMPLING_RATE, BIQUAD_Q, FILTER_BPF);
|
||||
}
|
||||
}
|
||||
|
||||
// used in OSD
|
||||
const gyroFftData_t *gyroFftData(int axis)
|
||||
{
|
||||
return &fftResult[axis];
|
||||
}
|
||||
|
||||
bool isDynamicFilterActive(void)
|
||||
{
|
||||
return feature(FEATURE_DYNAMIC_FILTER);
|
||||
}
|
||||
|
||||
/*
|
||||
* Collect gyro data, to be analysed in gyroDataAnalyseUpdate function
|
||||
*/
|
||||
void gyroDataAnalyse(const gyroDev_t *gyroDev, biquadFilter_t *notchFilterDyn)
|
||||
{
|
||||
if (!isDynamicFilterActive()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if gyro sampling is > 1kHz, accumulate multiple samples
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
fftAcc[axis] += gyroDev->gyroADC[axis];
|
||||
}
|
||||
fftAccCount++;
|
||||
|
||||
// this runs at 1kHz
|
||||
if (fftAccCount == fftSamplingScale) {
|
||||
fftAccCount = 0;
|
||||
|
||||
//calculate mean value of accumulated samples
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
float sample = fftAcc[axis] / fftSamplingScale;
|
||||
sample = biquadFilterApply(&fftGyroFilter[axis], sample);
|
||||
gyroData[axis][fftIdx] = sample;
|
||||
if (axis == 0)
|
||||
DEBUG_SET(DEBUG_FFT, 2, lrintf(sample * gyroDev->scale));
|
||||
fftAcc[axis] = 0;
|
||||
}
|
||||
|
||||
fftIdx = (fftIdx + 1) % FFT_WINDOW_SIZE;
|
||||
}
|
||||
|
||||
// calculate FFT and update filters
|
||||
gyroDataAnalyseUpdate(notchFilterDyn);
|
||||
}
|
||||
|
||||
void stage_rfft_f32(arm_rfft_fast_instance_f32 * S, float32_t * p, float32_t * pOut);
|
||||
void arm_cfft_radix8by2_f32( arm_cfft_instance_f32 * S, float32_t * p1);
|
||||
void arm_cfft_radix8by4_f32( arm_cfft_instance_f32 * S, float32_t * p1);
|
||||
void arm_radix8_butterfly_f32(float32_t * pSrc, uint16_t fftLen, const float32_t * pCoef, uint16_t twidCoefModifier);
|
||||
void arm_bitreversal_32(uint32_t * pSrc, const uint16_t bitRevLen, const uint16_t * pBitRevTable);
|
||||
|
||||
typedef enum {
|
||||
STEP_ARM_CFFT_F32,
|
||||
STEP_BITREVERSAL,
|
||||
STEP_STAGE_RFFT_F32,
|
||||
STEP_ARM_CMPLX_MAG_F32,
|
||||
STEP_CALC_FREQUENCIES,
|
||||
STEP_UPDATE_FILTERS,
|
||||
STEP_HANNING,
|
||||
STEP_COUNT
|
||||
} UpdateStep_e;
|
||||
|
||||
/*
|
||||
* Analyse last gyro data from the last FFT_WINDOW_SIZE milliseconds
|
||||
*/
|
||||
void gyroDataAnalyseUpdate(biquadFilter_t *notchFilterDyn)
|
||||
{
|
||||
static int axis = 0;
|
||||
static int step = 0;
|
||||
arm_cfft_instance_f32 * Sint = &(fftInstance.Sint);
|
||||
|
||||
uint32_t startTime = 0;
|
||||
if (debugMode == (DEBUG_FFT_TIME))
|
||||
startTime = micros();
|
||||
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 0, step);
|
||||
switch (step) {
|
||||
case STEP_ARM_CFFT_F32:
|
||||
{
|
||||
switch (FFT_WINDOW_SIZE / 2) {
|
||||
case 16:
|
||||
// 16us
|
||||
arm_cfft_radix8by2_f32(Sint, fftData);
|
||||
break;
|
||||
case 32:
|
||||
// 35us
|
||||
arm_cfft_radix8by4_f32(Sint, fftData);
|
||||
break;
|
||||
case 64:
|
||||
// 70us
|
||||
arm_radix8_butterfly_f32(fftData, FFT_WINDOW_SIZE / 2, Sint->pTwiddle, 1);
|
||||
break;
|
||||
}
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime);
|
||||
break;
|
||||
}
|
||||
case STEP_BITREVERSAL:
|
||||
{
|
||||
// 6us
|
||||
arm_bitreversal_32((uint32_t*) fftData, Sint->bitRevLength, Sint->pBitRevTable);
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime);
|
||||
step++;
|
||||
// fall through
|
||||
}
|
||||
case STEP_STAGE_RFFT_F32:
|
||||
{
|
||||
// 14us
|
||||
// this does not work in place => fftData AND rfftData needed
|
||||
stage_rfft_f32(&fftInstance, fftData, rfftData);
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime);
|
||||
break;
|
||||
}
|
||||
case STEP_ARM_CMPLX_MAG_F32:
|
||||
{
|
||||
// 8us
|
||||
arm_cmplx_mag_f32(rfftData, fftData, fftBinCount);
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 2, micros() - startTime);
|
||||
step++;
|
||||
// fall through
|
||||
}
|
||||
case STEP_CALC_FREQUENCIES:
|
||||
{
|
||||
// 13us
|
||||
float fftSum = 0;
|
||||
float fftWeightedSum = 0;
|
||||
|
||||
fftResult[axis].maxVal = 0;
|
||||
// iterate over fft data and calculate weighted indexes
|
||||
float squaredData;
|
||||
for (int i = 0; i < fftBinCount; i++) {
|
||||
squaredData = fftData[i] * fftData[i]; //more weight on higher peaks
|
||||
fftResult[axis].maxVal = MAX(fftResult[axis].maxVal, squaredData);
|
||||
fftSum += squaredData;
|
||||
fftWeightedSum += squaredData * (i + 1); // calculate weighted index starting at 1, not 0
|
||||
}
|
||||
|
||||
// get weighted center of relevant frequency range (this way we have a better resolution than 31.25Hz)
|
||||
if (fftSum > 0) {
|
||||
// idx was shifted by 1 to start at 1, not 0
|
||||
float fftMeanIndex = (fftWeightedSum / fftSum) - 1;
|
||||
// the index points at the center frequency of each bin so index 0 is actually 16.125Hz
|
||||
// fftMeanIndex += 0.5;
|
||||
|
||||
// don't go below the minimal cutoff frequency + 10 and don't jump around too much
|
||||
float centerFreq;
|
||||
centerFreq = constrain(fftMeanIndex * fftResolution, DYN_NOTCH_MIN_CUTOFF + 10, fftMaxFreq);
|
||||
centerFreq = biquadFilterApply(&fftFreqFilter[axis], centerFreq);
|
||||
centerFreq = constrain(centerFreq, DYN_NOTCH_MIN_CUTOFF + 10, fftMaxFreq);
|
||||
fftResult[axis].centerFreq = centerFreq;
|
||||
if (axis == 0) {
|
||||
DEBUG_SET(DEBUG_FFT, 3, lrintf(fftMeanIndex * 100));
|
||||
}
|
||||
}
|
||||
|
||||
DEBUG_SET(DEBUG_FFT_FREQ, axis, fftResult[axis].centerFreq);
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime);
|
||||
break;
|
||||
}
|
||||
case STEP_UPDATE_FILTERS:
|
||||
{
|
||||
// 7us
|
||||
// calculate new filter coefficients
|
||||
float cutoffFreq = constrain(fftResult[axis].centerFreq - DYN_NOTCH_WIDTH, DYN_NOTCH_MIN_CUTOFF, DYN_NOTCH_MAX_CUTOFF);
|
||||
float notchQ = filterGetNotchQApprox(fftResult[axis].centerFreq, cutoffFreq);
|
||||
biquadFilterUpdate(¬chFilterDyn[axis], fftResult[axis].centerFreq, gyro.targetLooptime, notchQ, FILTER_NOTCH);
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime);
|
||||
|
||||
axis = (axis + 1) % 3;
|
||||
step++;
|
||||
// fall through
|
||||
}
|
||||
case STEP_HANNING:
|
||||
{
|
||||
// 5us
|
||||
// apply hanning window to gyro samples and store result in fftData
|
||||
// hanning starts and ends with 0, could be skipped for minor speed improvement
|
||||
uint8_t ringBufIdx = FFT_WINDOW_SIZE - fftIdx;
|
||||
arm_mult_f32(&gyroData[axis][fftIdx], &hanningWindow[0], &fftData[0], ringBufIdx);
|
||||
if (fftIdx > 0)
|
||||
arm_mult_f32(&gyroData[axis][0], &hanningWindow[ringBufIdx], &fftData[ringBufIdx], fftIdx);
|
||||
|
||||
DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime);
|
||||
}
|
||||
}
|
||||
|
||||
step = (step + 1) % STEP_COUNT;
|
||||
}
|
||||
|
||||
#endif // USE_GYRO_DATA_ANALYSE
|
||||
|
|
|
@ -18,9 +18,17 @@
|
|||
#pragma once
|
||||
|
||||
#include "common/time.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
void gyroDataAnalyseInit(void);
|
||||
#define GYRO_FFT_BIN_COUNT 16 // FFT_WINDOW_SIZE / 2
|
||||
typedef struct gyroFftData_s {
|
||||
float maxVal;
|
||||
uint16_t centerFreq;
|
||||
} gyroFftData_t;
|
||||
|
||||
void gyroDataAnalyseInit(uint32_t targetLooptime);
|
||||
const gyroFftData_t *gyroFftData(int axis);
|
||||
struct gyroDev_s;
|
||||
struct gyro_s;
|
||||
void gyroDataAnalyse(const struct gyroDev_s *gyroDev, const struct gyro_s *gyro);
|
||||
void gyroDataAnalyseUpdate(timeUs_t currentTimeUs);
|
||||
void gyroDataAnalyse(const struct gyroDev_s *gyroDev, biquadFilter_t *notchFilterDyn);
|
||||
void gyroDataAnalyseUpdate(biquadFilter_t *notchFilterDyn);
|
||||
bool isDynamicFilterActive();
|
||||
|
|
|
@ -91,7 +91,7 @@
|
|||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA5
|
||||
//#define CURRENT_METER_ADC_PIN PA5
|
||||
|
|
|
@ -78,7 +78,7 @@
|
|||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
|
|
@ -25,9 +25,9 @@
|
|||
#include "drivers/timer_def.h"
|
||||
|
||||
// DSHOT will work for motor 1,3,4,5,6,7 and 8.
|
||||
// Motor 2 pin timers have no DMA channel assigned in the hardware.
|
||||
// If the ADC is used motor 7 will not work.
|
||||
// If UART1 is used motor 8 will not work.
|
||||
// Motor 2 pin timers have no DMA channel assigned in the hardware. Remapping of the pin is needed.
|
||||
// If SDCard or UART4 DMA is used motor 4 will not work.
|
||||
// If UART1 DMA is used motor 8 will not work.
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 1), // PWM1 - PA8 RC1 - DMA2_ST6, *DMA2_ST1, DMA2_ST3
|
||||
|
|
|
@ -109,8 +109,8 @@
|
|||
//#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC10
|
||||
#define UART4_TX_PIN PC11
|
||||
#define UART4_RX_PIN PC11
|
||||
#define UART4_TX_PIN PC10
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
|
@ -148,8 +148,9 @@
|
|||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
//#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
//#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
//#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC4
|
||||
|
|
|
@ -25,8 +25,7 @@
|
|||
#include "drivers/timer_def.h"
|
||||
|
||||
// DSHOT will work for motor 1-8.
|
||||
// If SDCard or UART4 DMA is used motor 6 will not work.
|
||||
// If the ADC is used motor 7 will not work.
|
||||
// If SDCard or UART4 DMA is used motor 7 will not work.
|
||||
// If UART1 DMA is used motor 8 will not work.
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
|
@ -36,8 +35,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM1, CH2N, PB14, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED , 0), // PWM3 - DMA2_ST6, DMA2_ST2
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM4 - DMA1_ST7
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM5 - DMA1_ST2
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6 - (DMA1_ST4) - DMA SDCard, DMA Serial_TX4
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7 - (DMA2_ST4) DMA2_ST2 - DMA ADC
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6 - (DMA2_ST4) DMA2_ST2
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7 - (DMA1_ST4) - DMA SDCard, DMA Serial_TX4
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM8 - (DMA2_ST7) - DMA Serial_TX1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM9 - (DMA1_ST2) - Collision
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED , 0), // PWM10 - (DMA2_ST6), (DMA2_ST6) - Collision
|
||||
|
|
|
@ -119,8 +119,8 @@
|
|||
//#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC10
|
||||
#define UART4_TX_PIN PC11
|
||||
#define UART4_RX_PIN PC11
|
||||
#define UART4_TX_PIN PC10
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
|
@ -158,8 +158,9 @@
|
|||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
//#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
//#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
//#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC4
|
||||
|
|
|
@ -131,7 +131,6 @@
|
|||
#define I2C1_SCL PB6
|
||||
#define I2C1_SDA PB7
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
|
||||
|
@ -147,6 +146,8 @@
|
|||
|
||||
#define DEFAULT_FEATURES ( FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_AIRMODE )
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
|
|
@ -110,8 +110,8 @@
|
|||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
#define HW_PIN PB2
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
|
||||
#define LED0 PB6
|
||||
#define LED1 PB5
|
||||
|
|
|
@ -103,8 +103,8 @@
|
|||
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC3
|
||||
|
|
|
@ -170,7 +170,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ BOXLLIGHTS, "LLIGHTS;", 16 },
|
||||
{ BOXCALIB, "CALIB;", 17 },
|
||||
{ BOXGOV, "GOVERNOR;", 18 },
|
||||
{ BOXOSD, "OSD SW;", 19 },
|
||||
{ BOXOSD, "OSD DISABLE SW;", 19 },
|
||||
{ BOXTELEMETRY, "TELEMETRY;", 20 },
|
||||
{ BOXGTUNE, "GTUNE;", 21 },
|
||||
{ BOXSONAR, "SONAR;", 22 },
|
||||
|
|
1
src/main/target/CRAZYFLIE2/CRAZYFLIE2BQ.mk
Normal file
1
src/main/target/CRAZYFLIE2/CRAZYFLIE2BQ.mk
Normal file
|
@ -0,0 +1 @@
|
|||
# CRAZYFLIE2BQ is a VARIANT of CRAZYFLIE2 with custom config for the BigQuad expansion deck (https://wiki.bitcraze.io/projects:crazyflie2:expansionboards:bigquad)
|
|
@ -21,18 +21,20 @@
|
|||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
#ifndef CRAZYFLIE2_USE_BIG_QUAD_DECK
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // PWM2 - OUT2 (Motor 2)
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // PWM1 - OUT1 (Motor 1)
|
||||
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // PWM3 - OUT3 (Motor 3)
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM4, NULL, 0, 0 }, // PWM4 - OUT4 (Motor 4)
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
DEF_TIM(TIM14, CH1, PA7, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // PWM1 - OUT1 (Motor 1)
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // PWM2 - OUT2 (Motor 2)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // PWM3 - OUT3 (Motor 3)
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // PWM4 - OUT4 (Motor 4)
|
||||
#else
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, NULL, 0, 0 }, // PWM2 - OUT2 (Motor 2)
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // PWM1 - OUT1 (Motor 1)
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, NULL, 0, 0 }, // PWM3 - OUT3 (Motor 3)
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // PWM4 - OUT4 (Motor 4)
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM1 - OUT1 (Motor 1)
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM2 - OUT2 (Motor 2)
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM3 - OUT3 (Motor 3)
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM4 - OUT4 (Motor 4)
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -26,21 +26,21 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
#define TARGET_BOARD_IDENTIFIER "CFBQ"
|
||||
#define USBD_PRODUCT_STRING "Crazyflie 2.0 (BigQuad Deck)"
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "CF20"
|
||||
|
||||
#define USBD_PRODUCT_STRING "Crazyflie 2.0"
|
||||
|
||||
// Uncomment this define to build for the Crazyflie
|
||||
// using the BigQuad expansion deck
|
||||
//#define CRAZYFLIE2_USE_BIG_QUAD_DECK
|
||||
#endif
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#ifndef CRAZYFLIE2_USE_BIG_QUAD_DECK
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(4) )
|
||||
#define BRUSHED_MOTORS
|
||||
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(14) )
|
||||
#else
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) )
|
||||
#endif //CRAZYFLIE2_USE_BIG_QUAD_DECK
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(4) )
|
||||
#endif
|
||||
|
||||
#define LED0 PD2
|
||||
#define LED1 PC0
|
||||
|
@ -55,19 +55,25 @@
|
|||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PA1
|
||||
#define UART2_RX_PIN PA3
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PB6
|
||||
#define UART1_RX_PIN PB7
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PC10
|
||||
#define UART3_RX_PIN PC11
|
||||
#endif
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
#else
|
||||
#define SERIAL_PORT_COUNT 2
|
||||
#endif
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_3
|
||||
|
@ -85,17 +91,34 @@
|
|||
#define USE_ACC_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||
|
||||
// Mag isn't working quite right -- disabling it for now
|
||||
//#define MAG
|
||||
//#define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus
|
||||
//#define USE_MAG_AK8963
|
||||
//#define MAG_AK8963_ALIGN CW270_DEG
|
||||
#define MAG
|
||||
#define USE_MPU9250_MAG // Enables bypass configuration on the MPU9250 I2C bus
|
||||
#define USE_MAG_AK8963
|
||||
#define MAG_AK8963_ALIGN CW270_DEG
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC13
|
||||
|
||||
#define USE_SERIALRX_TARGET_CUSTOM
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART6
|
||||
#define SERIALRX_PROVIDER SERIALRX_TARGET_CUSTOM
|
||||
#define RX_CHANNELS_TAER
|
||||
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#else
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#endif
|
||||
|
||||
#if defined(CRAZYFLIE2BQ)
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
#define VBAT_ADC_PIN PA6
|
||||
#else
|
||||
#define BRUSHED_MOTORS
|
||||
#endif
|
||||
|
|
|
@ -112,7 +112,7 @@
|
|||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC24_DMA_REMAP // moves ADC2 DMA from DMA2ch1 to DMA2ch3.
|
||||
|
|
|
@ -133,7 +133,7 @@
|
|||
#define I2C2_SCL PB10
|
||||
#define I2C2_SDA PB11
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -95,7 +95,7 @@
|
|||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD)
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#else
|
||||
|
||||
#define USE_SDCARD
|
||||
|
@ -159,7 +159,7 @@
|
|||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define VBAT_ADC_PIN PA0
|
||||
|
|
|
@ -170,7 +170,7 @@
|
|||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
|
|
|
@ -126,7 +126,7 @@
|
|||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
|
|
|
@ -80,7 +80,7 @@
|
|||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define CURRENT_METER_ADC_PIN PA0
|
||||
|
|
|
@ -72,7 +72,7 @@
|
|||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
|
|
@ -89,7 +89,7 @@
|
|||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
|
||||
#define BEEPER PC9
|
||||
#define BEEPER_INVERTED
|
||||
#define INVERTER_PIN_USART3 PB15
|
||||
#define INVERTER_PIN_UART3 PB15
|
||||
|
||||
// ICM20689 interrupt
|
||||
#define USE_EXTI
|
||||
|
@ -117,7 +117,7 @@
|
|||
#define USE_I2C_DEVICE_1
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_13
|
||||
|
|
|
@ -81,9 +81,8 @@
|
|||
#if defined(KIWIF4V2)
|
||||
#define USE_SDCARD
|
||||
|
||||
//#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PB9
|
||||
//#define SDCARD_DETECT_PIN PB9
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
|
||||
|
@ -165,7 +164,7 @@
|
|||
#define LED_STRIP
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
|
|
|
@ -85,8 +85,8 @@
|
|||
|
||||
#define OSD_CH_SWITCH PC5
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define BOARD_HAS_CURRENT_SENSOR
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define VBAT_ADC_PIN PC3
|
||||
|
|
9
src/main/target/LUMBAF3/readme.txt
Normal file
9
src/main/target/LUMBAF3/readme.txt
Normal file
|
@ -0,0 +1,9 @@
|
|||
|
||||
==LumbaF3==
|
||||
|
||||
Owner: miskoL
|
||||
|
||||
Board information:
|
||||
|
||||
- CPU - STM32F303CCT6
|
||||
- MPU-6000
|
39
src/main/target/LUMBAF3/target.c
Normal file
39
src/main/target/LUMBAF3/target.c
Normal file
|
@ -0,0 +1,39 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM | TIM_USE_TRANSPONDER, TIMER_INPUT_ENABLED), // PPM IN
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
|
||||
|
||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
|
||||
|
||||
DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, 1), // GPIO TIMER - LED_STRIP
|
||||
};
|
95
src/main/target/LUMBAF3/target.h
Normal file
95
src/main/target/LUMBAF3/target.h
Normal file
|
@ -0,0 +1,95 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "MCF3" // LumbaF3 Flight Controller by mC
|
||||
|
||||
#define LED0 PB3
|
||||
#define BEEPER PC15
|
||||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PA3
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define MPU6000_CS_GPIO GPIOA
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define M25P16_CS_GPIO GPIOB
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW90_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW90_DEG
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART3
|
||||
#define USE_SOFTSERIAL1
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
#undef USE_UART1_RX_DMA
|
||||
#endif
|
||||
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define SOFTSERIAL1_TX_PIN PB5
|
||||
#define SOFTSERIAL1_RX_PIN PB0
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA0
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define LED_STRIP
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
#define DEFAULT_FEATURES FEATURE_TELEMETRY
|
||||
|
||||
// IO - from schematics
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC ( BIT(14) | BIT(15) )
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 8
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) )
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
#define I2C2_SCL PB2
|
||||
#define I2C2_SDA PB1
|
6
src/main/target/LUMBAF3/target.mk
Normal file
6
src/main/target/LUMBAF3/target.mk
Normal file
|
@ -0,0 +1,6 @@
|
|||
F3_TARGETS += $(TARGET)
|
||||
FEATURES = ONBOARDFLASH VCP
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6000.c
|
|
@ -22,7 +22,7 @@
|
|||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "LUX"
|
||||
#endif
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
|
|
40
src/main/target/MATEKF405/target.c
Normal file
40
src/main/target/MATEKF405/target.c
Normal file
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S1 DMA1_ST4
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S2 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S3 DMA2_ST4
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S4 DMA2_ST7
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5 DMA1_ST5
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S6 DMA2_ST6
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED DMA1_ST0
|
||||
};
|
||||
|
144
src/main/target/MATEKF405/target.h
Normal file
144
src/main/target/MATEKF405/target.h
Normal file
|
@ -0,0 +1,144 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "MKF4"
|
||||
//#define CONFIG_START_FLASH_ADDRESS (0x08080000)
|
||||
|
||||
#define USBD_PRODUCT_STRING "MatekF4"
|
||||
|
||||
#define LED0 PB9
|
||||
#define LED1 PA14
|
||||
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** Gyro & ACC **********************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define MPU6500_CS_PIN PC2
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_EXTI
|
||||
#define MPU_INT_EXTI PC3
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
// *************** SD Card **************************
|
||||
#define USE_SDCARD
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PC1
|
||||
|
||||
// SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
|
||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7
|
||||
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
|
||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||
|
||||
// *************** OSD *****************************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI2
|
||||
#define MAX7456_SPI_CS_PIN PB10
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PB12
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PC11
|
||||
#define UART3_TX_PIN PC10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN PA0
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_RX_PIN PD2
|
||||
#define UART5_TX_PIN PC12
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
//#define SOFTSERIAL1_RX_PIN PA15 // S5
|
||||
//#define SOFTSERIAL1_TX_PIN PA8 // S6
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define VBAT_ADC_PIN PC5
|
||||
#define CURRENT_METER_ADC_PIN PC4
|
||||
#define RSSI_ADC_PIN PB1
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD )
|
||||
|
||||
#define LED_STRIP
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
#define BIND_PIN PA1 // USART4 RX
|
||||
|
||||
//#define USE_ESCSERIAL
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 8
|
||||
#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(5)|TIM_N(8))
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue