From c6c462b92f4e4149d60327e84d923027ce17aed3 Mon Sep 17 00:00:00 2001 From: Gary Keeble Date: Sat, 30 Apr 2016 09:34:30 +0100 Subject: [PATCH 01/85] Added SuperExpo Yaw field to header Added the super expo yaw field value and mode to header. --- src/main/blackbox/blackbox.c | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index e8306a4c45..496de037a0 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1195,7 +1195,7 @@ static bool blackboxWriteSysinfo() blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); break; case 19: - blackboxPrintfHeaderLine("superExpoFactor:%d", masterConfig.rxConfig.superExpoFactor); + blackboxPrintfHeaderLine("superExpoFactor:%d, %d", masterConfig.rxConfig.superExpoFactor, masterConfig.rxConfig.superExpoFactorYaw); break; case 20: blackboxPrintfHeaderLine("rates:%d,%d,%d", @@ -1333,6 +1333,9 @@ static bool blackboxWriteSysinfo() blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); break; case 52: + blackboxPrintfHeaderLine("superExpoYawMode:%d", masterConfig.rxConfig.superExpoYawMode); + break; + case 53: blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures); break; default: From 61392c5afca27efba162fc400f400f55f57d618d Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Thu, 28 Apr 2016 12:55:23 -0500 Subject: [PATCH 02/85] Removing inline from constrin and constrainf. These functions are used elsewhere and the inline declaration can cause the compiler to make them static and unavailable outside of this file. Unless these functions are defined in a .h file, they cannot be inlined. --- src/main/common/maths.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 3be8eff722..f54aeacdb7 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -111,7 +111,7 @@ int32_t applyDeadband(int32_t value, int32_t deadband) return value; } -inline int constrain(int amt, int low, int high) +int constrain(int amt, int low, int high) { if (amt < low) return low; @@ -121,7 +121,7 @@ inline int constrain(int amt, int low, int high) return amt; } -inline float constrainf(float amt, float low, float high) +float constrainf(float amt, float low, float high) { if (amt < low) return low; From b3216439de1a2023efb352eb34506ea4cc540f6e Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Thu, 28 Apr 2016 12:57:14 -0500 Subject: [PATCH 03/85] Allow the address of the start of the flash space to be defined externally. For testing, the flash memory can be allocated and defined to a different region than on an embedded processor. --- src/main/config/config.c | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/main/config/config.c b/src/main/config/config.c index 116692ee13..07cb5abbaf 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -124,8 +124,15 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000 #endif +// use the last flash pages for storage +#ifdef CUSTOM_FLASH_MEMORY_ADDRESS +size_t custom_flash_memory_address = 0; +#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) +#else // use the last flash pages for storage #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) +#endif + master_t masterConfig; // master config struct with data independent from profiles profile_t *currentProfile; From ac11732a869f57be1280938ab44acfaa0294e2b4 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Thu, 28 Apr 2016 12:58:37 -0500 Subject: [PATCH 04/85] Separate the initialization and main step into two different functions. For testing, it is useful to have the loop be separated from the initialization so that an external function can step through the main loop. --- src/main/main.c | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/src/main/main.c b/src/main/main.c index 49fc7c2466..56e9077d4e 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -26,7 +26,6 @@ #include "common/axis.h" #include "common/color.h" -#include "common/atomic.h" #include "common/maths.h" #include "drivers/nvic.h" @@ -658,7 +657,7 @@ void processLoopback(void) { #define processLoopback() #endif -int main(void) { +void main_init(void) { init(); /* Setup scheduler */ @@ -729,12 +728,22 @@ int main(void) { #ifdef USE_BST setTaskEnabled(TASK_BST_MASTER_PROCESS, true); #endif +} - while (1) { - scheduler(); - processLoopback(); +void main_step(void) { + scheduler(); + processLoopback(); +} + +#ifndef NOMAIN +int main(void) +{ + main_init(); + while(1) { + main_step(); } } +#endif #ifdef DEBUG_HARDFAULTS //from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ From 091aa24249a81ee70d4848513f1b15ecd9ccb906 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Thu, 28 Apr 2016 13:00:16 -0500 Subject: [PATCH 05/85] For fake gyro/acc, set the output to an fake variable. For testing, the gyros and accelerometer values might needed to be artifically set. This change allows a testing loop to set the gyro and acc to values through a global variable. --- src/main/sensors/initialisation.c | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 9c49090d4f..415ebbc4a4 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -214,6 +214,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) } #ifdef USE_FAKE_GYRO +int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 }; static void fakeGyroInit(uint16_t lpf) { UNUSED(lpf); @@ -221,7 +222,9 @@ static void fakeGyroInit(uint16_t lpf) static bool fakeGyroRead(int16_t *gyroADC) { - memset(gyroADC, 0, sizeof(int16_t[XYZ_AXIS_COUNT])); + for (int i = 0; i < XYZ_AXIS_COUNT; ++i) { + gyroADC[i] = fake_gyro_values[i]; + } return true; } @@ -241,9 +244,13 @@ bool fakeGyroDetect(gyro_t *gyro) #endif #ifdef USE_FAKE_ACC +int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0}; + static void fakeAccInit(void) {} static bool fakeAccRead(int16_t *accData) { - memset(accData, 0, sizeof(int16_t[XYZ_AXIS_COUNT])); + for(int i=0;i Date: Thu, 28 Apr 2016 13:50:03 -0500 Subject: [PATCH 06/85] Fixing null deref error when VBAT is not set. If VBAT is not configured, batteryConfig is null. This will possibly set the vbatPidCompensation to an unknown value. This change checkes for the validity of batteryConfig before defining the values to be used. --- src/main/flight/mixer.c | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 802e7e780e..813ec50f58 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -753,6 +753,11 @@ void mixTable(void) uint32_t i; fix12_t vbatCompensationFactor; static fix12_t mixReduction; + bool use_vbat_compensation = false; + if (batteryConfig && batteryConfig->vbatPidCompensation) { + use_vbat_compensation = true; + vbatCompensationFactor = calculateVbatPidCompensation(); + } bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code @@ -766,8 +771,6 @@ void mixTable(void) int16_t rollPitchYawMixMax = 0; // assumption: symetrical about zero. int16_t rollPitchYawMixMin = 0; - if (batteryConfig->vbatPidCompensation) vbatCompensationFactor = calculateVbatPidCompensation(); // Calculate voltage compensation - // Find roll/pitch/yaw desired output for (i = 0; i < motorCount; i++) { rollPitchYawMix[i] = @@ -775,7 +778,7 @@ void mixTable(void) axisPID[ROLL] * currentMixer[i].roll + -mixerConfig->yaw_motor_direction * axisPID[YAW] * currentMixer[i].yaw; - if (batteryConfig->vbatPidCompensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation + if (use_vbat_compensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation if (rollPitchYawMix[i] > rollPitchYawMixMax) rollPitchYawMixMax = rollPitchYawMix[i]; if (rollPitchYawMix[i] < rollPitchYawMixMin) rollPitchYawMixMin = rollPitchYawMix[i]; From b6ff69fedafcd9fd78ac9ea67e21736365e0edc5 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Mon, 2 May 2016 10:03:43 -0500 Subject: [PATCH 07/85] Moving constrain and constrainf to the include file to be inlined. --- src/main/common/maths.c | 20 -------------------- src/main/common/maths.h | 22 ++++++++++++++++++++++ 2 files changed, 22 insertions(+), 20 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index f54aeacdb7..888847e075 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -111,26 +111,6 @@ int32_t applyDeadband(int32_t value, int32_t deadband) return value; } -int constrain(int amt, int low, int high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} - -float constrainf(float amt, float low, float high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} - void devClear(stdev_t *dev) { dev->m_n = 0; diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 4a32e282c0..95f0ee8583 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -116,3 +116,25 @@ void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); int16_t qPercent(fix12_t q); int16_t qMultiply(fix12_t q, int16_t input); fix12_t qConstruct(int16_t num, int16_t den); + +// Defining constrain and constrainf as inline in the include file +// because these functions are used universally and should be fast. +inline int constrain(int amt, int low, int high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} + +inline float constrainf(float amt, float low, float high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} From d97d4dd544807ac2c6b82553c3cb77f484038eda Mon Sep 17 00:00:00 2001 From: nathan Date: Sat, 30 Apr 2016 12:16:02 -0700 Subject: [PATCH 08/85] hardfault handler w/ debugging info and an automatic breakpoint --- Makefile | 17 +- src/main/main.c | 61 +++ .../startup_stm32f3_debug_hardfault_handler.S | 501 ++++++++++++++++++ 3 files changed, 576 insertions(+), 3 deletions(-) create mode 100644 src/main/startup/startup_stm32f3_debug_hardfault_handler.S diff --git a/Makefile b/Makefile index 90217b59a8..723545eee2 100644 --- a/Makefile +++ b/Makefile @@ -28,6 +28,10 @@ OPBL ?=no # Debugger optons, must be empty or GDB DEBUG ?= +# Insert the debugging hardfault debugger +# releases should not be built with this flag as it does not disable pwm output +DEBUG_HARDFAULTS ?= + # Serial port/Device for flashing SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found) @@ -56,6 +60,13 @@ OPBL_VALID_TARGETS = CC3D_OPBL F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE +# note that there is no hardfault debugging startup file assembly handler for other platforms +ifeq ($(DEBUG_HARDFAULTS),F3) +CFLAGS += -DDEBUG_HARDFAULTS +STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S +else +STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S +endif # Configure default flash sizes for the targets ifeq ($(FLASH_SIZE),) @@ -534,8 +545,8 @@ CC3D_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) -STM32F30x_COMMON_SRC = \ - startup_stm32f30x_md_gcc.S \ + +STM32F30x_COMMON_SRC += \ drivers/adc.c \ drivers/adc_stm32f30x.c \ drivers/bus_i2c_stm32f30x.c \ @@ -816,7 +827,7 @@ endif DEBUG_FLAGS = -ggdb3 -DDEBUG -CFLAGS = $(ARCH_FLAGS) \ +CFLAGS += $(ARCH_FLAGS) \ $(LTO_FLAGS) \ $(addprefix -D,$(OPTIONS)) \ $(addprefix -I,$(INCLUDE_DIRS)) \ diff --git a/src/main/main.c b/src/main/main.c index 59158b2a55..49fc7c2466 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -736,6 +736,66 @@ int main(void) { } } +#ifdef DEBUG_HARDFAULTS +//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ +/** + * hard_fault_handler_c: + * This is called from the HardFault_HandlerAsm with a pointer the Fault stack + * as the parameter. We can then read the values from the stack and place them + * into local variables for ease of reading. + * We then read the various Fault Status and Address Registers to help decode + * cause of the fault. + * The function ends with a BKPT instruction to force control back into the debugger + */ +void hard_fault_handler_c(unsigned long *hardfault_args){ + volatile unsigned long stacked_r0 ; + volatile unsigned long stacked_r1 ; + volatile unsigned long stacked_r2 ; + volatile unsigned long stacked_r3 ; + volatile unsigned long stacked_r12 ; + volatile unsigned long stacked_lr ; + volatile unsigned long stacked_pc ; + volatile unsigned long stacked_psr ; + volatile unsigned long _CFSR ; + volatile unsigned long _HFSR ; + volatile unsigned long _DFSR ; + volatile unsigned long _AFSR ; + volatile unsigned long _BFAR ; + volatile unsigned long _MMAR ; + + stacked_r0 = ((unsigned long)hardfault_args[0]) ; + stacked_r1 = ((unsigned long)hardfault_args[1]) ; + stacked_r2 = ((unsigned long)hardfault_args[2]) ; + stacked_r3 = ((unsigned long)hardfault_args[3]) ; + stacked_r12 = ((unsigned long)hardfault_args[4]) ; + stacked_lr = ((unsigned long)hardfault_args[5]) ; + stacked_pc = ((unsigned long)hardfault_args[6]) ; + stacked_psr = ((unsigned long)hardfault_args[7]) ; + + // Configurable Fault Status Register + // Consists of MMSR, BFSR and UFSR + _CFSR = (*((volatile unsigned long *)(0xE000ED28))) ; + + // Hard Fault Status Register + _HFSR = (*((volatile unsigned long *)(0xE000ED2C))) ; + + // Debug Fault Status Register + _DFSR = (*((volatile unsigned long *)(0xE000ED30))) ; + + // Auxiliary Fault Status Register + _AFSR = (*((volatile unsigned long *)(0xE000ED3C))) ; + + // Read the Fault Address Registers. These may not contain valid values. + // Check BFARVALID/MMARVALID to see if they are valid values + // MemManage Fault Address Register + _MMAR = (*((volatile unsigned long *)(0xE000ED34))) ; + // Bus Fault Address Register + _BFAR = (*((volatile unsigned long *)(0xE000ED38))) ; + + __asm("BKPT #0\n") ; // Break into the debugger +} + +#else void HardFault_Handler(void) { // fall out of the sky @@ -753,3 +813,4 @@ void HardFault_Handler(void) while (1); } +#endif diff --git a/src/main/startup/startup_stm32f3_debug_hardfault_handler.S b/src/main/startup/startup_stm32f3_debug_hardfault_handler.S new file mode 100644 index 0000000000..65ee39a670 --- /dev/null +++ b/src/main/startup/startup_stm32f3_debug_hardfault_handler.S @@ -0,0 +1,501 @@ +/** + ****************************************************************************** + * @file startup_stm32f30x.s + * @author MCD Application Team + * @version V1.0.0 + * @date 04-Spetember-2012 + * @brief STM32F30x Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3230C-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2012 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +.global HardFault_Handler +.extern hard_fault_handler_c + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr r0, =0x20009FFC // HJI 11/9/2012 + ldr r1, =0xDEADBEEF // HJI 11/9/2012 + ldr r2, [r0, #0] // HJI 11/9/2012 + str r0, [r0, #0] // HJI 11/9/2012 + cmp r2, r1 // HJI 11/9/2012 + beq Reboot_Loader // HJI 11/9/2012 + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr + +LoopForever: + b LoopForever + +Reboot_Loader: // HJI 11/9/2012 + + // Reboot to ROM // HJI 11/9/2012 + ldr r0, =0x1FFFD800 // HJI 4/26/2013 + ldr sp,[r0, #0] // HJI 11/9/2012 + ldr r0,[r0, #4] // HJI 11/9/2012 + bx r0 // HJI 11/9/2012 + +.size Reset_Handler, .-Reset_Handler + +.section .text.Reset_Handler +.weak HardFault_Handler +.type HardFault_Handler, %function +HardFault_Handler: + movs r0,#4 + movs r1, lr + tst r0, r1 + beq _MSP + mrs r0, psp + b _HALT +_MSP: + mrs r0, msp +_HALT: + ldr r1,[r0,#20] + b hard_fault_handler_c + bkpt #0 + +.size HardFault_Handler, .-HardFault_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M4. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_STAMP_IRQHandler + .word RTC_WKUP_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_TS_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTC_Alarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word 0 + .word 0 + .word 0 + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_IRQHandler + .word DMA2_Channel5_IRQHandler + .word ADC4_IRQHandler + .word 0 + .word 0 + .word COMP1_2_3_IRQHandler + .word COMP4_5_6_IRQHandler + .word COMP7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word USB_HP_IRQHandler + .word USB_LP_IRQHandler + .word USBWakeUp_RMP_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word FPU_IRQHandler + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_STAMP_IRQHandler + .thumb_set TAMPER_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_TS_IRQHandler + .thumb_set EXTI2_TS_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak ADC4_IRQHandler + .thumb_set ADC4_IRQHandler,Default_Handler + + .weak COMP1_2_3_IRQHandler + .thumb_set COMP1_2_3_IRQHandler,Default_Handler + + .weak COMP4_5_6_IRQHandler + .thumb_set COMP4_5_6_IRQHandler,Default_Handler + + .weak COMP7_IRQHandler + .thumb_set COMP7_IRQHandler,Default_Handler + + .weak USB_HP_IRQHandler + .thumb_set USB_HP_IRQHandler,Default_Handler + + .weak USB_LP_IRQHandler + .thumb_set USB_LP_IRQHandler,Default_Handler + + .weak USBWakeUp_RMP_IRQHandler + .thumb_set USBWakeUp_RMP_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 08e87a40cf1c88dfba8bfff57f4a2b5c21148c0f Mon Sep 17 00:00:00 2001 From: nathan Date: Sat, 30 Apr 2016 12:34:55 -0700 Subject: [PATCH 09/85] dont try to check the gyro status if the gyro doesnt support interrupts --- src/main/drivers/gyro_sync.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/gyro_sync.c b/src/main/drivers/gyro_sync.c index 1047442c0b..934708f379 100644 --- a/src/main/drivers/gyro_sync.c +++ b/src/main/drivers/gyro_sync.c @@ -32,7 +32,8 @@ static uint8_t mpuDividerDrops; bool getMpuDataStatus(gyro_t *gyro) { bool mpuDataStatus; - + if (!gyro->intStatus) + return false; gyro->intStatus(&mpuDataStatus); return mpuDataStatus; } From 2264494fca03269fbf1ddd12e6b9513545f217e9 Mon Sep 17 00:00:00 2001 From: nathan Date: Sat, 30 Apr 2016 12:35:09 -0700 Subject: [PATCH 10/85] duplicate file --- Makefile | 1 - 1 file changed, 1 deletion(-) diff --git a/Makefile b/Makefile index 723545eee2..d5bfb1d006 100644 --- a/Makefile +++ b/Makefile @@ -575,7 +575,6 @@ STM32F3DISCOVERY_COMMON_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ drivers/accgyro_l3gd20.c \ - drivers/accgyro_l3gd20.c \ drivers/accgyro_lsm303dlhc.c \ drivers/compass_hmc5883l.c \ $(VCP_SRC) From 9b3aecbffcfb2f6bc5cc68cda60e4d76151d4d6e Mon Sep 17 00:00:00 2001 From: nathan Date: Sat, 30 Apr 2016 12:41:43 -0700 Subject: [PATCH 11/85] print the target name so we can figure out which target is breaking w/ fake_travis_build.sh --- fake_travis_build.sh | 3 +++ 1 file changed, 3 insertions(+) diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 2a6a9b275e..9d1fe66169 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -26,6 +26,9 @@ export TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/simulated} for target in "${targets[@]}" do unset RUNTESTS PUBLISHMETA TARGET + echo + echo + echo "BUILDING '$target'" eval "export $target" make -f Makefile clean ./.travis.sh From e1f52d9c7bc60668a0118db92c61c731f308dcc5 Mon Sep 17 00:00:00 2001 From: nathan Date: Sat, 30 Apr 2016 14:33:36 -0700 Subject: [PATCH 12/85] guess we need some defines --- src/main/target/STM32F3DISCOVERY/target.h | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 8a812d879c..190676ef3f 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -152,6 +152,20 @@ #define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3 #define EXTERNAL1_ADC_CHANNEL ADC_Channel_9 +#define LED_STRIP +#define LED_STRIP_TIMER TIM16 +#define WS2811_GPIO GPIOB +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM16 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 +#define WS2811_DMA_CHANNEL DMA1_Channel3 +#define WS2811_IRQ DMA1_Channel3_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER + #define BLACKBOX #define GPS //#define GTUNE From 3dd6424f34706f1bc62fd9b80c09f067b26e99bc Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Sat, 30 Apr 2016 12:54:15 +0200 Subject: [PATCH 13/85] Revert "Fixed a bug which caused printing of floats larger than 100 in the CLI to crash" This reverts commit 6ce8fe3c0fa7725e77d6ea61557bcec65d6cdb34. --- src/main/common/typeconversion.c | 5 ----- src/main/common/typeconversion.h | 10 ---------- src/main/io/serial_cli.c | 2 +- 3 files changed, 1 insertion(+), 16 deletions(-) diff --git a/src/main/common/typeconversion.c b/src/main/common/typeconversion.c index 3a3730fd56..4e3f8b4c2e 100644 --- a/src/main/common/typeconversion.c +++ b/src/main/common/typeconversion.c @@ -144,11 +144,6 @@ char *itoa(int i, char *a, int base) #endif -/* Note: the floatString must be at least 13 bytes long to cover all cases. - * This includes up to 10 digits (32 bit ints can hold numbers up to 10 - * digits long) + the decimal point + negative sign or space + null - * terminator. - */ char *ftoa(float x, char *floatString) { int32_t value; diff --git a/src/main/common/typeconversion.h b/src/main/common/typeconversion.h index f2811d65ba..62b437875b 100644 --- a/src/main/common/typeconversion.h +++ b/src/main/common/typeconversion.h @@ -21,17 +21,7 @@ void li2a(long num, char *bf); void ui2a(unsigned int num, unsigned int base, int uc, char *bf); void i2a(int num, char *bf); char a2i(char ch, const char **src, int base, int *nump); - -/* Simple conversion of a float to a string. Will display completely - * inaccurate results for floats larger than about 2.15E6 (2^31 / 1000) - * (same thing for negative values < -2.15E6). - * Will always display 3 decimals, so anything smaller than 1E-3 will - * not be displayed. - * The floatString will be filled in with the result and will be - * returned. It must be at least 13 bytes in length to cover all cases! - */ char *ftoa(float x, char *floatString); - float fastA2F(const char *p); #ifndef HAVE_ITOA_FUNCTION diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 2f837ed9ef..d3a7e79c20 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -2448,7 +2448,7 @@ static void cliWrite(uint8_t ch) static void cliPrintVar(const clivalue_t *var, uint32_t full) { int32_t value = 0; - char buf[13]; + char buf[8]; void *ptr = var->ptr; if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) { From 29865701daa6553aa4da2b18653aa4cb9a1f0aa5 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Sat, 30 Apr 2016 23:19:00 +0200 Subject: [PATCH 14/85] Change Filter lowpass Frequency to int --- src/main/config/config.c | 9 ++++----- src/main/config/config_master.h | 4 ++-- src/main/flight/mixer.h | 2 +- src/main/flight/pid.h | 4 ++-- src/main/io/serial_cli.c | 6 +++--- 5 files changed, 12 insertions(+), 13 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 116692ee13..fc6fe12183 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -134,7 +134,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 133; +static const uint8_t EEPROM_CONF_VERSION = 134; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -177,12 +177,11 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->D8[PIDVEL] = 75; pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; - pidProfile->yaw_lpf_hz = 70.0f; - pidProfile->dterm_differentiator = 1; + pidProfile->yaw_lpf_hz = 100; pidProfile->rollPitchItermResetRate = 200; pidProfile->rollPitchItermResetAlways = 0; pidProfile->yawItermResetRate = 50; - pidProfile->dterm_lpf_hz = 70.0f; // filtering ON by default + pidProfile->dterm_lpf_hz = 70; // filtering ON by default pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes @@ -403,7 +402,7 @@ static void resetConf(void) masterConfig.dcm_ki = 0; // 0.003 * 10000 masterConfig.gyro_lpf = 0; // 256HZ default masterConfig.gyro_sync_denom = 8; - masterConfig.gyro_soft_lpf_hz = 80.0f; + masterConfig.gyro_soft_lpf_hz = 80; masterConfig.pid_process_denom = 1; diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 4af7851e4f..281a7fa3d5 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -56,9 +56,9 @@ typedef struct master_t { int8_t yaw_control_direction; // change control direction of yaw (inverted, normal) uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes. - uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. + uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. uint8_t gyro_sync_denom; // Gyro sample divider - float gyro_soft_lpf_hz; // Biqyad gyro lpf hz + uint8_t gyro_soft_lpf_hz; // Biqyad gyro lpf hz uint16_t dcm_kp; // DCM filter proportional gain ( x 10000) uint16_t dcm_ki; // DCM filter integral gain ( x 10000) diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index eb324c6768..36dca92263 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -74,7 +74,7 @@ typedef struct mixerConfig_s { uint16_t yaw_jump_prevention_limit; // make limit configurable (original fixed value was 100) #ifdef USE_SERVOS uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed - int16_t servo_lowpass_freq; // lowpass servo filter frequency selection; 1/1000ths of loop freq + uint16_t servo_lowpass_freq; // lowpass servo filter frequency selection; 1/1000ths of loop freq int8_t servo_lowpass_enable; // enable/disable lowpass filter #endif } mixerConfig_t; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 94addfb55d..3f9bb7ef72 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -74,8 +74,8 @@ typedef struct pidProfile_s { uint8_t H_sensitivity; - float dterm_lpf_hz; // Delta Filter in hz - float yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy + uint16_t dterm_lpf_hz; // Delta Filter in hz + uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy uint16_t rollPitchItermResetRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates uint8_t rollPitchItermResetAlways; // Reset Iterm also without SUPER EXPO uint16_t yawItermResetRate; // Experimental threshold for resetting iterm for yaw on certain rates diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index d3a7e79c20..dc75498913 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -653,7 +653,7 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } }, { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } }, - { "gyro_lowpass_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } }, + { "gyro_lowpass_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } }, { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } }, { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } }, { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } }, @@ -673,7 +673,7 @@ const clivalue_t valueTable[] = { { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } }, #ifdef USE_SERVOS { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } }, - { "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} }, + { "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} }, { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } }, #endif @@ -726,7 +726,7 @@ const clivalue_t valueTable[] = { { "iterm_always_reset", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } }, { "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } }, { "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } }, - { "yaw_lowpass_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, + { "yaw_lowpass_hz", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } }, { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } }, From ad756bceb4f4cbe5eb357901145000e053f05d2d Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Sun, 1 May 2016 00:10:03 +0200 Subject: [PATCH 15/85] New version --- src/main/version.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/version.h b/src/main/version.h index 587b442c73..922d94b1d7 100644 --- a/src/main/version.h +++ b/src/main/version.h @@ -16,8 +16,8 @@ */ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) -#define FC_VERSION_MINOR 6 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed +#define FC_VERSION_MINOR 7 // increment when a minor release is made (small new feature, change etc) +#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) From a4456ce6b9b8abcccfce5abe940bc3a7b27c2ba8 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Sat, 30 Apr 2016 23:20:06 +0200 Subject: [PATCH 16/85] Initial dynamic PID implementation New Defaults and some rework in dynamic PID Cli Fixes Copy / Paste Protection Change Stick threshold Remove differentiator Change Default PIDs --- src/main/blackbox/blackbox.c | 4 +-- src/main/config/config.c | 17 +++++----- src/main/flight/pid.c | 64 +++++++++++++++--------------------- src/main/flight/pid.h | 7 ++-- src/main/io/serial_cli.c | 10 +++--- src/main/io/serial_msp.c | 2 +- src/main/mw.c | 14 +------- 7 files changed, 48 insertions(+), 70 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index e73f69387e..a84b3768fb 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1280,8 +1280,8 @@ static bool blackboxWriteSysinfo() masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); break; case 36: - blackboxPrintfHeaderLine("dterm_differentiator:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_differentiator); + blackboxPrintfHeaderLine("dynamic_pterm:%d", + masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pterm); break; case 37: blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", diff --git a/src/main/config/config.c b/src/main/config/config.c index fc6fe12183..4d6c046128 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -148,10 +148,10 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->pidController = 1; pidProfile->P8[ROLL] = 45; - pidProfile->I8[ROLL] = 30; + pidProfile->I8[ROLL] = 35; pidProfile->D8[ROLL] = 18; pidProfile->P8[PITCH] = 45; - pidProfile->I8[PITCH] = 30; + pidProfile->I8[PITCH] = 35; pidProfile->D8[PITCH] = 18; pidProfile->P8[YAW] = 90; pidProfile->I8[YAW] = 40; @@ -177,11 +177,12 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->D8[PIDVEL] = 75; pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; - pidProfile->yaw_lpf_hz = 100; + pidProfile->yaw_lpf_hz = 70; pidProfile->rollPitchItermResetRate = 200; pidProfile->rollPitchItermResetAlways = 0; pidProfile->yawItermResetRate = 50; pidProfile->dterm_lpf_hz = 70; // filtering ON by default + pidProfile->dynamic_pterm = 1; pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes @@ -307,9 +308,9 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcExpo8 = 60; controlRateConfig->thrMid8 = 50; controlRateConfig->thrExpo8 = 0; - controlRateConfig->dynThrPID = 0; + controlRateConfig->dynThrPID = 20; controlRateConfig->rcYawExpo8 = 20; - controlRateConfig->tpa_breakpoint = 1500; + controlRateConfig->tpa_breakpoint = 1650; for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) { controlRateConfig->rates[axis] = 50; @@ -401,10 +402,10 @@ static void resetConf(void) masterConfig.dcm_kp = 2500; // 1.0 * 10000 masterConfig.dcm_ki = 0; // 0.003 * 10000 masterConfig.gyro_lpf = 0; // 256HZ default - masterConfig.gyro_sync_denom = 8; - masterConfig.gyro_soft_lpf_hz = 80; + masterConfig.gyro_sync_denom = 4; + masterConfig.gyro_soft_lpf_hz = 100; - masterConfig.pid_process_denom = 1; + masterConfig.pid_process_denom = 2; masterConfig.debug_mode = 0; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 0246fa71f1..cc3312820e 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -93,6 +93,16 @@ float calculateExpoPlus(int axis, rxConfig_t *rxConfig) { return propFactor; } +uint16_t getDynamicKp(int axis, pidProfile_t *pidProfile) { + uint16_t dynamicKp; + + uint32_t dynamicFactor = constrain(ABS(rcCommand[axis] << 8) / DYNAMIC_PTERM_STICK_THRESHOLD, 0, 1 << 7); + + dynamicKp = ((pidProfile->P8[axis] << 8) + (pidProfile->P8[axis] * dynamicFactor)) >> 8; + + return dynamicKp; +} + void pidResetErrorAngle(void) { errorAngleI[ROLL] = 0; @@ -136,7 +146,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa { float RateError, AngleRate, gyroRate; float ITerm,PTerm,DTerm; - static float lastRate[3][PID_LAST_RATE_COUNT]; + static float lastRate[3]; float delta; int axis; float horizonLevelStrength = 1; @@ -200,11 +210,13 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa // multiplication of rcCommand corresponds to changing the sticks scaling here RateError = AngleRate - gyroRate; + uint16_t kP = (pidProfile->dynamic_pterm) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; + // -----calculate P component if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { - PTerm = (luxPTermScale * pidProfile->P8[axis] * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig)); + PTerm = (luxPTermScale * kP * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig)); } else { - PTerm = luxPTermScale * RateError * pidProfile->P8[axis] * tpaFactor; + PTerm = luxPTermScale * RateError * kP * tpaFactor; } // Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply @@ -220,7 +232,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa } if (axis == YAW) { - if (ABS(gyroRate / 4.1f) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -ITERM_RESET_THRESHOLD_YAW, ITERM_RESET_THRESHOLD_YAW); + if (ABS(gyroRate / 4.1f) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -ITERM_RESET_THRESHOLD, ITERM_RESET_THRESHOLD); } if (antiWindupProtection || motorLimitReached) { @@ -238,20 +250,8 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); DTerm = 0; } else { - if (pidProfile->dterm_differentiator) { - // Calculate derivative using noise-robust differentiator without time delay (one-sided or forward filters) - // by Pavel Holoborodko, see http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/ - // N=5: h[0] = 3/8, h[-1] = 1/2, h[-2] = -1/2, h[-3] = -3/4, h[-4] = 1/8, h[-5] = 1/4 - delta = -(3*gyroRate + 4*lastRate[axis][0] - 4*lastRate[axis][1] - 6*lastRate[axis][2] + 1*lastRate[axis][3] + 2*lastRate[axis][4]) / 8; - for (int i = PID_LAST_RATE_COUNT - 1; i > 0; i--) { - lastRate[axis][i] = lastRate[axis][i-1]; - } - } else { - // When DTerm low pass filter disabled apply moving average to reduce noise - delta = -(gyroRate - lastRate[axis][0]); - } - - lastRate[axis][0] = gyroRate; + delta = -(gyroRate - lastRate[axis]); + lastRate[axis] = gyroRate; // Divide delta by targetLooptime to get differential (ie dr/dt) delta *= (1.0f / getdT()); @@ -288,7 +288,7 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co int axis; int32_t PTerm, ITerm, DTerm, delta; - static int32_t lastRate[3][PID_LAST_RATE_COUNT]; + static int32_t lastRate[3]; int32_t AngleRateTmp, RateError, gyroRate; int8_t horizonLevelStrength = 100; @@ -342,11 +342,13 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co gyroRate = gyroADC[axis] / 4; RateError = AngleRateTmp - gyroRate; + uint16_t kP = (pidProfile->dynamic_pterm) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; + // -----calculate P component if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { - PTerm = (pidProfile->P8[axis] * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig))) >> 7; + PTerm = (kP * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig))) >> 7; } else { - PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7; + PTerm = (RateError * kP * PIDweight[axis] / 100) >> 7; } // Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply @@ -366,11 +368,11 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13); if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) { - if (ABS(gyroRate *10 / 41) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], -ITERM_RESET_THRESHOLD, ITERM_RESET_THRESHOLD); + if (ABS(gyroRate *10 / 41) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -ITERM_RESET_THRESHOLD << 13, (int32_t) + ITERM_RESET_THRESHOLD << 13); } if (axis == YAW) { - if (ABS(gyroRate * 10 / 41) >= pidProfile->yawItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], -ITERM_RESET_THRESHOLD_YAW, ITERM_RESET_THRESHOLD_YAW); + if (ABS(gyroRate * 10 / 41) >= pidProfile->yawItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -ITERM_RESET_THRESHOLD << 13, (int32_t) + ITERM_RESET_THRESHOLD << 13); } if (antiWindupProtection || motorLimitReached) { @@ -386,20 +388,8 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); DTerm = 0; } else { - if (pidProfile->dterm_differentiator) { - // Calculate derivative using noise-robust differentiator without time delay (one-sided or forward filters) - // by Pavel Holoborodko, see http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/ - // N=5: h[0] = 3/8, h[-1] = 1/2, h[-2] = -1/2, h[-3] = -3/4, h[-4] = 1/8, h[-5] = 1/4 - delta = -(3*gyroRate + 4*lastRate[axis][0] - 4*lastRate[axis][1] - 6*lastRate[axis][2] + 1*lastRate[axis][3] + 2*lastRate[axis][4]) / 8; - for (int i = PID_LAST_RATE_COUNT - 1; i > 0; i--) { - lastRate[axis][i] = lastRate[axis][i-1]; - } - } else { - // When DTerm low pass filter disabled apply moving average to reduce noise - delta = -(gyroRate - lastRate[axis][0]); - } - - lastRate[axis][0] = gyroRate; + delta = -(gyroRate - lastRate[axis]); + lastRate[axis] = gyroRate; // Divide delta by targetLooptime to get differential (ie dr/dt) delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 3f9bb7ef72..3738f97633 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -22,9 +22,8 @@ #define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter #define YAW_P_LIMIT_MAX 400 // Maximum value for yaw P limiter -#define PID_LAST_RATE_COUNT 7 -#define ITERM_RESET_THRESHOLD 20 -#define ITERM_RESET_THRESHOLD_YAW 10 +#define ITERM_RESET_THRESHOLD 15 +#define DYNAMIC_PTERM_STICK_THRESHOLD 400 typedef enum { PIDROLL, @@ -81,7 +80,7 @@ typedef struct pidProfile_s { uint16_t yawItermResetRate; // Experimental threshold for resetting iterm for yaw on certain rates uint16_t yaw_p_limit; uint8_t dterm_average_count; // Configurable delta count for dterm - uint8_t dterm_differentiator; + uint8_t dynamic_pterm; #ifdef GTUNE uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index dc75498913..71583fbad2 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -653,7 +653,7 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } }, { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } }, - { "gyro_lowpass_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } }, + { "gyro_lowpass", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } }, { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } }, { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } }, { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } }, @@ -721,12 +721,12 @@ const clivalue_t valueTable[] = { { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } }, { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } }, - { "dterm_lowpass_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } }, - { "dterm_differentiator", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_differentiator, .config.lookup = { TABLE_OFF_ON } }, - { "iterm_always_reset", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } }, + { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } }, + { "dynamic_pterm", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dynamic_pterm, .config.lookup = { TABLE_OFF_ON } }, + { "iterm_always_reset", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } }, { "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } }, { "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } }, - { "yaw_lowpass_hz", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, + { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } }, { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } }, diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index c782124307..d44dc8e9aa 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -152,7 +152,7 @@ void setGyroSamplingSpeed(uint16_t looptime) { masterConfig.pid_process_denom = 1; if (currentProfile->pidProfile.pidController == 2) masterConfig.pid_process_denom = 2; if (looptime < 250) { - masterConfig.pid_process_denom = 3; + masterConfig.pid_process_denom = 4; } else if (looptime < 375) { if (currentProfile->pidProfile.pidController == 2) { masterConfig.pid_process_denom = 3; diff --git a/src/main/mw.c b/src/main/mw.c index 80d588baf4..7e8dfcd380 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -770,17 +770,6 @@ uint8_t setPidUpdateCountDown(void) { } } -// Check for oneshot125 protection. With fast looptimes oneshot125 pulse duration gets more near the pid looptime -bool shouldUpdateMotorsAfterPIDLoop(void) { - if (targetPidLooptime > 375 ) { - return true; - } else if ((masterConfig.use_multiShot || masterConfig.use_oneshot42) && feature(FEATURE_ONESHOT125)) { - return true; - } else { - return false; - } -} - // Function for loop trigger void taskMainPidLoopCheck(void) { static uint32_t previousTime; @@ -801,7 +790,6 @@ void taskMainPidLoopCheck(void) { static uint8_t pidUpdateCountdown; if (runTaskMainSubprocesses) { - if (!shouldUpdateMotorsAfterPIDLoop()) taskMotorUpdate(); subTasksMainPidLoop(); runTaskMainSubprocesses = false; } @@ -813,7 +801,7 @@ void taskMainPidLoopCheck(void) { } else { pidUpdateCountdown = setPidUpdateCountDown(); taskMainPidLoop(); - if (shouldUpdateMotorsAfterPIDLoop()) taskMotorUpdate(); + taskMotorUpdate(); runTaskMainSubprocesses = true; } From 5ffb3b5068568d49eba97ec023040ca10cea6a7e Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 4 May 2016 00:00:04 +0200 Subject: [PATCH 17/85] Revert "Merge pull request #372 from aughey/betaflight" This reverts commit a6a5f50ffbd470175e8dae9e17e4d5f4424996f9, reversing changes made to 9cc55038516f52896ece099b6959a3413c25891f. --- src/main/common/maths.c | 20 ++++++++++++++++++++ src/main/common/maths.h | 22 ---------------------- src/main/config/config.c | 7 ------- src/main/flight/mixer.c | 9 +++------ src/main/main.c | 19 +++++-------------- src/main/sensors/initialisation.c | 11 ++--------- 6 files changed, 30 insertions(+), 58 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 888847e075..3be8eff722 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -111,6 +111,26 @@ int32_t applyDeadband(int32_t value, int32_t deadband) return value; } +inline int constrain(int amt, int low, int high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} + +inline float constrainf(float amt, float low, float high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} + void devClear(stdev_t *dev) { dev->m_n = 0; diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 95f0ee8583..4a32e282c0 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -116,25 +116,3 @@ void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); int16_t qPercent(fix12_t q); int16_t qMultiply(fix12_t q, int16_t input); fix12_t qConstruct(int16_t num, int16_t den); - -// Defining constrain and constrainf as inline in the include file -// because these functions are used universally and should be fast. -inline int constrain(int amt, int low, int high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} - -inline float constrainf(float amt, float low, float high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} diff --git a/src/main/config/config.c b/src/main/config/config.c index 7844c0795b..4d6c046128 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -124,15 +124,8 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000 #endif -// use the last flash pages for storage -#ifdef CUSTOM_FLASH_MEMORY_ADDRESS -size_t custom_flash_memory_address = 0; -#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) -#else // use the last flash pages for storage #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) -#endif - master_t masterConfig; // master config struct with data independent from profiles profile_t *currentProfile; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 813ec50f58..802e7e780e 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -753,11 +753,6 @@ void mixTable(void) uint32_t i; fix12_t vbatCompensationFactor; static fix12_t mixReduction; - bool use_vbat_compensation = false; - if (batteryConfig && batteryConfig->vbatPidCompensation) { - use_vbat_compensation = true; - vbatCompensationFactor = calculateVbatPidCompensation(); - } bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code @@ -771,6 +766,8 @@ void mixTable(void) int16_t rollPitchYawMixMax = 0; // assumption: symetrical about zero. int16_t rollPitchYawMixMin = 0; + if (batteryConfig->vbatPidCompensation) vbatCompensationFactor = calculateVbatPidCompensation(); // Calculate voltage compensation + // Find roll/pitch/yaw desired output for (i = 0; i < motorCount; i++) { rollPitchYawMix[i] = @@ -778,7 +775,7 @@ void mixTable(void) axisPID[ROLL] * currentMixer[i].roll + -mixerConfig->yaw_motor_direction * axisPID[YAW] * currentMixer[i].yaw; - if (use_vbat_compensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation + if (batteryConfig->vbatPidCompensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation if (rollPitchYawMix[i] > rollPitchYawMixMax) rollPitchYawMixMax = rollPitchYawMix[i]; if (rollPitchYawMix[i] < rollPitchYawMixMin) rollPitchYawMixMin = rollPitchYawMix[i]; diff --git a/src/main/main.c b/src/main/main.c index 56e9077d4e..49fc7c2466 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -26,6 +26,7 @@ #include "common/axis.h" #include "common/color.h" +#include "common/atomic.h" #include "common/maths.h" #include "drivers/nvic.h" @@ -657,7 +658,7 @@ void processLoopback(void) { #define processLoopback() #endif -void main_init(void) { +int main(void) { init(); /* Setup scheduler */ @@ -728,22 +729,12 @@ void main_init(void) { #ifdef USE_BST setTaskEnabled(TASK_BST_MASTER_PROCESS, true); #endif -} -void main_step(void) { - scheduler(); - processLoopback(); -} - -#ifndef NOMAIN -int main(void) -{ - main_init(); - while(1) { - main_step(); + while (1) { + scheduler(); + processLoopback(); } } -#endif #ifdef DEBUG_HARDFAULTS //from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 415ebbc4a4..9c49090d4f 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -214,7 +214,6 @@ const extiConfig_t *selectMPUIntExtiConfig(void) } #ifdef USE_FAKE_GYRO -int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 }; static void fakeGyroInit(uint16_t lpf) { UNUSED(lpf); @@ -222,9 +221,7 @@ static void fakeGyroInit(uint16_t lpf) static bool fakeGyroRead(int16_t *gyroADC) { - for (int i = 0; i < XYZ_AXIS_COUNT; ++i) { - gyroADC[i] = fake_gyro_values[i]; - } + memset(gyroADC, 0, sizeof(int16_t[XYZ_AXIS_COUNT])); return true; } @@ -244,13 +241,9 @@ bool fakeGyroDetect(gyro_t *gyro) #endif #ifdef USE_FAKE_ACC -int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0}; - static void fakeAccInit(void) {} static bool fakeAccRead(int16_t *accData) { - for(int i=0;i Date: Tue, 3 May 2016 17:44:49 -0500 Subject: [PATCH 18/85] Moving constrain to the include file and making it static inline --- src/main/common/maths.c | 20 -------------------- src/main/common/maths.h | 23 ++++++++++++++++++++--- 2 files changed, 20 insertions(+), 23 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 3be8eff722..888847e075 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -111,26 +111,6 @@ int32_t applyDeadband(int32_t value, int32_t deadband) return value; } -inline int constrain(int amt, int low, int high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} - -inline float constrainf(float amt, float low, float high) -{ - if (amt < low) - return low; - else if (amt > high) - return high; - else - return amt; -} - void devClear(stdev_t *dev) { dev->m_n = 0; diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 4a32e282c0..3251c237a8 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -71,9 +71,6 @@ typedef union { int32_t applyDeadband(int32_t value, int32_t deadband); -int constrain(int amt, int low, int high); -float constrainf(float amt, float low, float high); - void devClear(stdev_t *dev); void devPush(stdev_t *dev, float x); float devVariance(stdev_t *dev); @@ -116,3 +113,23 @@ void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); int16_t qPercent(fix12_t q); int16_t qMultiply(fix12_t q, int16_t input); fix12_t qConstruct(int16_t num, int16_t den); + +static inline int constrain(int amt, int low, int high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} + +static inline float constrainf(float amt, float low, float high) +{ + if (amt < low) + return low; + else if (amt > high) + return high; + else + return amt; +} From fd245bb8f8977bc6728b0d3753cdb63c91390325 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Tue, 3 May 2016 17:45:13 -0500 Subject: [PATCH 19/85] Allowing a custom flash memory address for offline testing. --- src/main/config/config.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/main/config/config.c b/src/main/config/config.c index 4d6c046128..c1db3534fa 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -124,8 +124,14 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000 #endif +// use the last flash pages for storage +#ifdef CUSTOM_FLASH_MEMORY_ADDRESS +size_t custom_flash_memory_address = 0; +#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) +#else // use the last flash pages for storage #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) +#endif master_t masterConfig; // master config struct with data independent from profiles profile_t *currentProfile; From cb39345dd37b0ef06943d7f18efcc7b939a621c7 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Tue, 3 May 2016 17:45:37 -0500 Subject: [PATCH 20/85] Fixing a null dereference in the case that VBAT is not defined --- src/main/flight/mixer.c | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 802e7e780e..6240d85532 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -751,8 +751,13 @@ STATIC_UNIT_TESTED void servoMixer(void) void mixTable(void) { uint32_t i; - fix12_t vbatCompensationFactor; + fix12_t vbatCompensationFactor = 0; static fix12_t mixReduction; + bool use_vbat_compensation = false; + if (batteryConfig && batteryConfig->vbatPidCompensation) { + use_vbat_compensation = true; + vbatCompensationFactor = calculateVbatPidCompensation(); + } bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code @@ -766,7 +771,7 @@ void mixTable(void) int16_t rollPitchYawMixMax = 0; // assumption: symetrical about zero. int16_t rollPitchYawMixMin = 0; - if (batteryConfig->vbatPidCompensation) vbatCompensationFactor = calculateVbatPidCompensation(); // Calculate voltage compensation + if (use_vbat_compensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation // Find roll/pitch/yaw desired output for (i = 0; i < motorCount; i++) { @@ -775,7 +780,7 @@ void mixTable(void) axisPID[ROLL] * currentMixer[i].roll + -mixerConfig->yaw_motor_direction * axisPID[YAW] * currentMixer[i].yaw; - if (batteryConfig->vbatPidCompensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation + if (use_vbat_compensation) rollPitchYawMix[i] = qMultiply(vbatCompensationFactor, rollPitchYawMix[i]); // Add voltage compensation if (rollPitchYawMix[i] > rollPitchYawMixMax) rollPitchYawMixMax = rollPitchYawMix[i]; if (rollPitchYawMix[i] < rollPitchYawMixMin) rollPitchYawMixMin = rollPitchYawMix[i]; From faf1c9a6d24abf64ba1aca73c1e8b9bdeb152a5a Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Tue, 3 May 2016 17:46:56 -0500 Subject: [PATCH 21/85] Breaking out the main init and main loop to allow for offline testing --- src/main/main.c | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/src/main/main.c b/src/main/main.c index 49fc7c2466..ab02994433 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -26,7 +26,6 @@ #include "common/axis.h" #include "common/color.h" -#include "common/atomic.h" #include "common/maths.h" #include "drivers/nvic.h" @@ -658,7 +657,7 @@ void processLoopback(void) { #define processLoopback() #endif -int main(void) { +void main_init(void) { init(); /* Setup scheduler */ @@ -729,12 +728,24 @@ int main(void) { #ifdef USE_BST setTaskEnabled(TASK_BST_MASTER_PROCESS, true); #endif +} - while (1) { - scheduler(); - processLoopback(); +void main_step(void) +{ + scheduler(); + processLoopback(); +} + +#ifndef NOMAIN +int main(void) +{ + main_init(); + while(1) { + main_step(); } } +#endif + #ifdef DEBUG_HARDFAULTS //from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ From 70130a1bcb56cc07a89c510e3d95b5e3eb9220a9 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Tue, 3 May 2016 17:47:16 -0500 Subject: [PATCH 22/85] Allowing the fake gyro and accel values to be set externally --- src/main/sensors/initialisation.c | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 9c49090d4f..85b5ebb307 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -214,6 +214,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) } #ifdef USE_FAKE_GYRO +int16_t fake_gyro_values[XYZ_AXIS_COUNT] = { 0,0,0 }; static void fakeGyroInit(uint16_t lpf) { UNUSED(lpf); @@ -221,7 +222,10 @@ static void fakeGyroInit(uint16_t lpf) static bool fakeGyroRead(int16_t *gyroADC) { - memset(gyroADC, 0, sizeof(int16_t[XYZ_AXIS_COUNT])); + for (int i = 0; i < XYZ_AXIS_COUNT; ++i) { + gyroADC[i] = fake_gyro_values[i]; + } + return true; } @@ -241,9 +245,13 @@ bool fakeGyroDetect(gyro_t *gyro) #endif #ifdef USE_FAKE_ACC +int16_t fake_acc_values[XYZ_AXIS_COUNT] = {0,0,0}; static void fakeAccInit(void) {} static bool fakeAccRead(int16_t *accData) { - memset(accData, 0, sizeof(int16_t[XYZ_AXIS_COUNT])); + for(int i=0;i Date: Wed, 4 May 2016 10:39:07 +0200 Subject: [PATCH 23/85] Fix data type for gyro lowpass // Defaults --- src/main/config/config.c | 4 ++-- src/main/io/serial_cli.c | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 4d6c046128..88bf765706 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -181,7 +181,7 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->rollPitchItermResetRate = 200; pidProfile->rollPitchItermResetAlways = 0; pidProfile->yawItermResetRate = 50; - pidProfile->dterm_lpf_hz = 70; // filtering ON by default + pidProfile->dterm_lpf_hz = 80; // filtering ON by default pidProfile->dynamic_pterm = 1; pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes @@ -403,7 +403,7 @@ static void resetConf(void) masterConfig.dcm_ki = 0; // 0.003 * 10000 masterConfig.gyro_lpf = 0; // 256HZ default masterConfig.gyro_sync_denom = 4; - masterConfig.gyro_soft_lpf_hz = 100; + masterConfig.gyro_soft_lpf_hz = 85; masterConfig.pid_process_denom = 2; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 71583fbad2..3f0bb134dc 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -653,7 +653,7 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } }, { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } }, - { "gyro_lowpass", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } }, + { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } }, { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } }, { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } }, { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } }, From 8c7c72c5dc4cd69c24546121b8f20e5a469019a4 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 4 May 2016 10:12:11 +0100 Subject: [PATCH 24/85] Tidy of main pid loop. --- src/main/flight/imu.c | 5 ----- src/main/flight/imu.h | 2 -- src/main/mw.c | 50 ++++++++++++++++--------------------------- 3 files changed, 19 insertions(+), 38 deletions(-) diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index d72331ddd1..0906c4ac47 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -419,11 +419,6 @@ void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims) } } -void imuUpdateGyro(void) -{ - gyroUpdate(); -} - void imuUpdateAttitude(void) { if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) { diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 3f64b5c50d..6dc0a1f6b7 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -79,7 +79,6 @@ void imuConfigure( float getCosTiltAngle(void); void calculateEstimatedAltitude(uint32_t currentTime); void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims); -void imuUpdateGyro(void); void imuUpdateAttitude(void); float calculateThrottleAngleScale(uint16_t throttle_correction_angle); int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value); @@ -88,5 +87,4 @@ float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_hz); int16_t imuCalculateHeading(t_fp_vector *vec); void imuResetAccelerationSum(void); -void imuUpdateGyro(void); void imuUpdateAcc(rollAndPitchTrims_t *accelerometerTrims); diff --git a/src/main/mw.c b/src/main/mw.c index 7e8dfcd380..ae407cf710 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -653,13 +653,8 @@ void processRx(void) } -#if defined(BARO) || defined(SONAR) -static bool haveProcessedAnnexCodeOnce = false; -#endif - -void taskMainPidLoop(void) +void subTaskPidController(void) { - // PID - note this is function pointer set by setPIDController() pid_controller( ¤tProfile->pidProfile, @@ -668,20 +663,14 @@ void taskMainPidLoop(void) &masterConfig.accelerometerTrims, &masterConfig.rxConfig ); - - mixTable(); } -void subTasksMainPidLoop(void) { +void subTaskMainSubprocesses(void) { if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) { filterRc(); } - #if defined(BARO) || defined(SONAR) - haveProcessedAnnexCodeOnce = true; - #endif - #ifdef MAG if (sensors(SENSOR_MAG)) { updateMagHold(); @@ -743,7 +732,8 @@ void subTasksMainPidLoop(void) { #endif } -void taskMotorUpdate(void) { +void subTaskMotorUpdate(void) +{ if (debugMode == DEBUG_CYCLETIME) { static uint32_t previousMotorUpdateTime; uint32_t currentDeltaTime = micros() - previousMotorUpdateTime; @@ -752,6 +742,8 @@ void taskMotorUpdate(void) { previousMotorUpdateTime = micros(); } + mixTable(); + #ifdef USE_SERVOS filterServos(); writeServos(); @@ -771,11 +763,12 @@ uint8_t setPidUpdateCountDown(void) { } // Function for loop trigger -void taskMainPidLoopCheck(void) { +void taskMainPidLoopCheck(void) +{ static uint32_t previousTime; static bool runTaskMainSubprocesses; - uint32_t currentDeltaTime = getTaskDeltaTime(TASK_SELF); + const uint32_t currentDeltaTime = getTaskDeltaTime(TASK_SELF); cycleTime = micros() - previousTime; previousTime = micros(); @@ -790,18 +783,18 @@ void taskMainPidLoopCheck(void) { static uint8_t pidUpdateCountdown; if (runTaskMainSubprocesses) { - subTasksMainPidLoop(); + subTaskMainSubprocesses(); runTaskMainSubprocesses = false; } - imuUpdateGyro(); + gyroUpdate(); if (pidUpdateCountdown) { pidUpdateCountdown--; } else { pidUpdateCountdown = setPidUpdateCountDown(); - taskMainPidLoop(); - taskMotorUpdate(); + subTaskPidController(); + subTaskMotorUpdate(); runTaskMainSubprocesses = true; } @@ -862,24 +855,19 @@ void taskUpdateRxMain(void) processRx(); isRXDataNew = true; + // the 'annexCode' initialses rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState + annexCode(); #ifdef BARO - // the 'annexCode' initialses rcCommand, updateAltHoldState depends on valid rcCommand data. - if (haveProcessedAnnexCodeOnce) { - if (sensors(SENSOR_BARO)) { - updateAltHoldState(); - } + if (sensors(SENSOR_BARO)) { + updateAltHoldState(); } #endif #ifdef SONAR - // the 'annexCode' initialses rcCommand, updateAltHoldState depends on valid rcCommand data. - if (haveProcessedAnnexCodeOnce) { - if (sensors(SENSOR_SONAR)) { - updateSonarAltHoldState(); - } + if (sensors(SENSOR_SONAR)) { + updateSonarAltHoldState(); } #endif - annexCode(); } #ifdef GPS From 2bae11d581b90de7d6804b6513b6af754b17e2d1 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 4 May 2016 20:21:06 +0100 Subject: [PATCH 25/85] Added tasks page to OLED display. --- src/main/io/display.c | 40 ++++++++++++++++++++++++++++++++++++++++ src/main/io/display.h | 3 +++ 2 files changed, 43 insertions(+) diff --git a/src/main/io/display.c b/src/main/io/display.c index 55c4d15283..33fc5e5fcf 100644 --- a/src/main/io/display.c +++ b/src/main/io/display.c @@ -64,6 +64,8 @@ #include "display.h" +#include "scheduler.h" + controlRateConfig_t *getControlRateConfig(uint8_t profileIndex); #define MICROSECONDS_IN_A_SECOND (1000 * 1000) @@ -90,6 +92,9 @@ static const char* const pageTitles[] = { "SENSORS", "RX", "PROFILE" +#ifndef SKIP_TASK_STATISTICS + ,"TASKS" +#endif #ifdef GPS ,"GPS" #endif @@ -108,6 +113,9 @@ const pageId_e cyclePageIds[] = { PAGE_RX, PAGE_BATTERY, PAGE_SENSORS +#ifndef SKIP_TASK_STATISTICS + ,PAGE_TASKS +#endif #ifdef ENABLE_DEBUG_OLED_PAGE ,PAGE_DEBUG, #endif @@ -514,6 +522,33 @@ void showSensorsPage(void) } +#ifndef SKIP_TASK_STATISTICS +void showTasksPage(void) +{ + uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; + static const char *format = "%2d%6d%5d%4d%4d"; + + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string("Task max avg mx% av%"); + cfTaskInfo_t taskInfo; + for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; ++taskId) { + getTaskInfo(taskId, &taskInfo); + if (taskInfo.isEnabled && taskId != TASK_SERIAL) {// don't waste a line of the display showing serial taskInfo + const int taskFrequency = (int)(1000000.0f / ((float)taskInfo.latestDeltaTime)); + const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 10000; + const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 10000; + tfp_sprintf(lineBuffer, format, taskId, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, maxLoad, averageLoad); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + if (rowIndex > SCREEN_CHARACTER_ROW_COUNT) { + break; + } + } + } +} +#endif + #ifdef ENABLE_DEBUG_OLED_PAGE void showDebugPage(void) @@ -605,6 +640,11 @@ void updateDisplay(void) case PAGE_PROFILE: showProfilePage(); break; +#ifndef SKIP_TASK_STATISTICS + case PAGE_TASKS: + showTasksPage(); + break; +#endif #ifdef GPS case PAGE_GPS: if (feature(FEATURE_GPS)) { diff --git a/src/main/io/display.h b/src/main/io/display.h index b4bac0e08e..7d420b6563 100644 --- a/src/main/io/display.h +++ b/src/main/io/display.h @@ -24,6 +24,9 @@ typedef enum { PAGE_SENSORS, PAGE_RX, PAGE_PROFILE, +#ifndef SKIP_TASK_STATISTICS + PAGE_TASKS, +#endif #ifdef GPS PAGE_GPS, #endif From f62ec043cfc4f91a237081d3ea4cb6805d4f792d Mon Sep 17 00:00:00 2001 From: rav-rav Date: Wed, 4 May 2016 22:44:33 +0200 Subject: [PATCH 26/85] fix error in biquad coefficients calculation improve biquad precision and performance by using direct form 2 transposed instead of direct form 1 keep float results for luxfloat pid controller, instead of casting twice --- src/main/common/filter.c | 39 ++++++++++++++++----------------------- src/main/common/filter.h | 2 +- src/main/flight/pid.c | 2 +- src/main/sensors/gyro.c | 6 +++++- src/main/sensors/gyro.h | 1 + 5 files changed, 24 insertions(+), 26 deletions(-) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 7d26d2ca8f..21fd2948f8 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -28,6 +28,7 @@ #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*/ // PT1 Low Pass filter (when no dT specified it will be calculated from the cycleTime) float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dT) { @@ -56,44 +57,36 @@ void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate) omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate; sn = sinf(omega); cs = cosf(omega); - alpha = sn * sinf(M_LN2_FLOAT /2 * BIQUAD_BANDWIDTH * omega /sn); + //this is wrong, should be hyperbolic sine + //alpha = sn * sinf(M_LN2_FLOAT /2 * BIQUAD_BANDWIDTH * omega /sn); + alpha = sn / (2 * BIQUAD_Q); - b0 = (1 - cs) /2; + b0 = (1 - cs) / 2; b1 = 1 - cs; - b2 = (1 - cs) /2; + b2 = (1 - cs) / 2; a0 = 1 + alpha; a1 = -2 * cs; a2 = 1 - alpha; /* precompute the coefficients */ - newState->b0 = b0 /a0; - newState->b1 = b1 /a0; - newState->b2 = b2 /a0; - newState->a1 = a1 /a0; - newState->a2 = a2 /a0; + newState->b0 = b0 / a0; + newState->b1 = b1 / a0; + newState->b2 = b2 / a0; + newState->a1 = a1 / a0; + newState->a2 = a2 / a0; /* zero initial samples */ - newState->x1 = newState->x2 = 0; - newState->y1 = newState->y2 = 0; + newState->d1 = newState->d2 = 1; } /* Computes a biquad_t filter on a sample */ -float applyBiQuadFilter(float sample, biquad_t *state) +float applyBiQuadFilter(float sample, biquad_t *state) //direct form 2 transposed { float result; - /* compute result */ - result = state->b0 * sample + state->b1 * state->x1 + state->b2 * state->x2 - - state->a1 * state->y1 - state->a2 * state->y2; - - /* shift x1 to x2, sample to x1 */ - state->x2 = state->x1; - state->x1 = sample; - - /* shift y1 to y2, result to y1 */ - state->y2 = state->y1; - state->y1 = result; - + result = state->b0 * sample + state->d1; + state->d1 = state->b1 * sample - state->a1 * result + state->d2; + state->d2 = state->b2 * sample - state->a2 * result; return result; } diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 5009956026..809063f4b0 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -26,7 +26,7 @@ typedef struct filterStatePt1_s { /* this holds the data required to update samples thru a filter */ typedef struct biquad_s { float b0, b1, b2, a1, a2; - float x1, x2, y1, y2; + float d1, d2; } biquad_t; float applyBiQuadFilter(float sample, biquad_t *state); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index cc3312820e..091eda0876 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -202,7 +202,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa } } - gyroRate = gyroADC[axis] / 4.0f; // gyro output scaled to rewrite scale + gyroRate = gyroADCf[axis] / 4.0f; // gyro output scaled to rewrite scale // --------low-level gyro-based PID. ---------- // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index de34127604..17981d5883 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -38,6 +38,7 @@ uint16_t calibratingG = 0; int32_t gyroADC[XYZ_AXIS_COUNT]; +float gyroADCf[XYZ_AXIS_COUNT]; int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 }; static gyroConfig_t *gyroConfig; @@ -155,7 +156,10 @@ void gyroUpdate(void) if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */ if (gyroFilterStateIsSet) { - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) gyroADC[axis] = lrintf(applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis])); + for (axis = 0; axis < XYZ_AXIS_COUNT; axis++){ + gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]); + gyroADC[axis] = lrintf(gyroADCf[axis]); + } } } diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 48e5e677e2..05f78706f8 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -33,6 +33,7 @@ extern gyro_t gyro; extern sensor_align_e gyroAlign; extern int32_t gyroADC[XYZ_AXIS_COUNT]; +extern float gyroADCf[XYZ_AXIS_COUNT]; extern int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT]; typedef struct gyroConfig_s { From 771f2c61eb23cc82863cbc0d7a9f4b1b24bfe190 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 4 May 2016 23:39:19 +0200 Subject: [PATCH 27/85] Fix out of order PPM ISR // Fix PPM for SPRACINGF3EVO --- src/main/config/config.c | 2 +- src/main/drivers/pwm_rx.c | 91 +++++++++++++++++++++++++++++++++------ 2 files changed, 79 insertions(+), 14 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 88bf765706..d8d2f8c5a1 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -403,7 +403,7 @@ static void resetConf(void) masterConfig.dcm_ki = 0; // 0.003 * 10000 masterConfig.gyro_lpf = 0; // 256HZ default masterConfig.gyro_sync_denom = 4; - masterConfig.gyro_soft_lpf_hz = 85; + masterConfig.gyro_soft_lpf_hz = 90; masterConfig.pid_process_denom = 2; diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index b87fecd11c..df91273f2e 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -20,8 +20,9 @@ #include -#include "platform.h" +#include #include "build_config.h" +#include "debug.h" #include "common/utils.h" @@ -35,16 +36,18 @@ #include "pwm_rx.h" +#define DEBUG_PPM_ISR + #define PPM_CAPTURE_COUNT 12 #define PWM_INPUT_PORT_COUNT 8 -#if PPM_CAPTURE_COUNT > MAX_PWM_INPUT_PORTS +#if PPM_CAPTURE_COUNT > PWM_INPUT_PORT_COUNT #define PWM_PORTS_OR_PPM_CAPTURE_COUNT PPM_CAPTURE_COUNT #else #define PWM_PORTS_OR_PPM_CAPTURE_COUNT PWM_INPUT_PORT_COUNT #endif -// TODO - change to timer cloks ticks +// TODO - change to timer clocks ticks #define INPUT_FILTER_TO_HELP_WITH_NOISE_FROM_OPENLRS_TELEMETRY_RX 0x03 static inputFilteringMode_e inputFilteringMode; @@ -85,7 +88,8 @@ static uint8_t ppmCountShift = 0; typedef struct ppmDevice_s { uint8_t pulseIndex; - uint32_t previousTime; + //uint32_t previousTime; + uint32_t currentCapture; uint32_t currentTime; uint32_t deltaTime; uint32_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT]; @@ -95,6 +99,7 @@ typedef struct ppmDevice_s { uint8_t stableFramesSeenCount; bool tracking; + bool overflowed; } ppmDevice_t; ppmDevice_t ppmDev; @@ -125,10 +130,35 @@ void pwmRxInit(inputFilteringMode_e initialInputFilteringMode) inputFilteringMode = initialInputFilteringMode; } +#ifdef DEBUG_PPM_ISR +typedef enum { + SOURCE_OVERFLOW = 0, + SOURCE_EDGE = 1 +} eventSource_e; + +typedef struct ppmISREvent_s { + eventSource_e source; + uint32_t capture; +} ppmISREvent_t; + +static ppmISREvent_t ppmEvents[20]; +static uint8_t ppmEventIndex = 0; + +void ppmISREvent(eventSource_e source, uint32_t capture) +{ + ppmEventIndex = (ppmEventIndex + 1) % (sizeof(ppmEvents) / sizeof(ppmEvents[0])); + + ppmEvents[ppmEventIndex].source = source; + ppmEvents[ppmEventIndex].capture = capture; +} +#else +void ppmISREvent(eventSource_e source, uint32_t capture) {} +#endif + static void ppmInit(void) { ppmDev.pulseIndex = 0; - ppmDev.previousTime = 0; + ppmDev.currentCapture = 0; ppmDev.currentTime = 0; ppmDev.deltaTime = 0; ppmDev.largeCounter = 0; @@ -136,42 +166,77 @@ static void ppmInit(void) ppmDev.numChannelsPrevFrame = -1; ppmDev.stableFramesSeenCount = 0; ppmDev.tracking = false; + ppmDev.overflowed = false; } static void ppmOverflowCallback(timerOvrHandlerRec_t* cbRec, captureCompare_t capture) { UNUSED(cbRec); + ppmISREvent(SOURCE_OVERFLOW, capture); + ppmDev.largeCounter += capture + 1; + if (capture == PPM_TIMER_PERIOD - 1) { + ppmDev.overflowed = true; + } + } static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture) { UNUSED(cbRec); + ppmISREvent(SOURCE_EDGE, capture); + int32_t i; - /* Shift the last measurement out */ - ppmDev.previousTime = ppmDev.currentTime; + uint32_t previousTime = ppmDev.currentTime; + uint32_t previousCapture = ppmDev.currentCapture; /* Grab the new count */ - ppmDev.currentTime = capture; + uint32_t currentTime = capture; /* Convert to 32-bit timer result */ - ppmDev.currentTime += ppmDev.largeCounter; + currentTime += ppmDev.largeCounter; + + if (capture < previousCapture) { + if (ppmDev.overflowed) { + currentTime += PPM_TIMER_PERIOD; + } + } // Divide by 8 if Oneshot125 is active and this is a CC3D board - ppmDev.currentTime = ppmDev.currentTime >> ppmCountShift; + currentTime = currentTime >> ppmCountShift; /* Capture computation */ - ppmDev.deltaTime = ppmDev.currentTime - ppmDev.previousTime; + if (currentTime > previousTime) { + ppmDev.deltaTime = currentTime - (previousTime + (ppmDev.overflowed ? (PPM_TIMER_PERIOD >> ppmCountShift) : 0)); + } else { + ppmDev.deltaTime = (PPM_TIMER_PERIOD >> ppmCountShift) + currentTime - previousTime; + } - ppmDev.previousTime = ppmDev.currentTime; + ppmDev.overflowed = false; -#if 0 + + /* Store the current measurement */ + ppmDev.currentTime = currentTime; + ppmDev.currentCapture = capture; + +#if 1 static uint32_t deltaTimes[20]; static uint8_t deltaIndex = 0; deltaIndex = (deltaIndex + 1) % 20; deltaTimes[deltaIndex] = ppmDev.deltaTime; + UNUSED(deltaTimes); +#endif + + +#if 1 + static uint32_t captureTimes[20]; + static uint8_t captureIndex = 0; + + captureIndex = (captureIndex + 1) % 20; + captureTimes[captureIndex] = capture; + UNUSED(captureTimes); #endif /* Sync pulse detection */ From 825475fd438b32b4ba076d2dc84577d4ef47414b Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 5 May 2016 10:28:26 +0100 Subject: [PATCH 28/85] Added new debug mode to time pidloop subtasks. --- src/main/debug.h | 7 +++-- src/main/flight/pid.c | 20 ++++++-------- src/main/flight/pid.h | 1 - src/main/io/display.c | 26 ++++++++++++++---- src/main/io/display.h | 2 +- src/main/io/serial_cli.c | 6 ++-- src/main/mw.c | 14 ++++++++-- src/main/scheduler.h | 6 ++-- src/main/scheduler_tasks.c | 52 +++++++++++++++++------------------ src/main/target/CC3D/target.h | 42 ++++++++++++---------------- 10 files changed, 98 insertions(+), 78 deletions(-) diff --git a/src/main/debug.h b/src/main/debug.h index facb9982ec..4f6250b758 100644 --- a/src/main/debug.h +++ b/src/main/debug.h @@ -42,10 +42,13 @@ extern uint32_t sectionTimes[2][4]; #endif typedef enum { - DEBUG_CYCLETIME = 1, + DEBUG_NONE, + DEBUG_CYCLETIME, DEBUG_BATTERY, DEBUG_GYRO, DEBUG_ACCELEROMETER, DEBUG_MIXER, - DEBUG_AIRMODE + DEBUG_AIRMODE, + DEBUG_PIDLOOP, + DEBUG_COUNT } debugType_e; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 091eda0876..0a5cf87db5 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -62,9 +62,10 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; uint8_t PIDweight[3]; static int32_t errorGyroI[3], errorGyroILimit[3]; +#ifndef SKIP_PID_LUXFLOAT static float errorGyroIf[3], errorGyroIfLimit[3]; -static int32_t errorAngleI[2]; -static float errorAngleIf[2]; +#endif + static bool lowThrottlePidReduction; static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, @@ -103,22 +104,15 @@ uint16_t getDynamicKp(int axis, pidProfile_t *pidProfile) { return dynamicKp; } -void pidResetErrorAngle(void) -{ - errorAngleI[ROLL] = 0; - errorAngleI[PITCH] = 0; - - errorAngleIf[ROLL] = 0.0f; - errorAngleIf[PITCH] = 0.0f; -} - void pidResetErrorGyroState(uint8_t resetOption) { if (resetOption >= RESET_ITERM) { int axis; for (axis = 0; axis < 3; axis++) { errorGyroI[axis] = 0; +#ifndef SKIP_PID_LUXFLOAT errorGyroIf[axis] = 0.0f; +#endif } } @@ -141,6 +135,7 @@ const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; static filterStatePt1_t deltaFilterState[3]; static filterStatePt1_t yawFilterState; +#ifndef SKIP_PID_LUXFLOAT static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) { @@ -280,6 +275,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa #endif } } +#endif static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) @@ -426,8 +422,10 @@ void pidSetController(pidControllerType_e type) case PID_CONTROLLER_MWREWRITE: pid_controller = pidMultiWiiRewrite; break; +#ifndef SKIP_PID_LUXFLOAT case PID_CONTROLLER_LUX_FLOAT: pid_controller = pidLuxFloat; +#endif } } diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 3738f97633..14df2b8f41 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -97,7 +97,6 @@ bool antiWindupProtection; extern uint32_t targetPidLooptime; void pidSetController(pidControllerType_e type); -void pidResetErrorAngle(void); void pidResetErrorGyroState(uint8_t resetOption); void setTargetPidLooptime(uint8_t pidProcessDenom); diff --git a/src/main/io/display.c b/src/main/io/display.c index 33fc5e5fcf..ed394d9c95 100644 --- a/src/main/io/display.c +++ b/src/main/io/display.c @@ -22,6 +22,7 @@ #include "platform.h" #include "version.h" +#include "debug.h" #include "build_config.h" @@ -58,14 +59,16 @@ #include "flight/navigation.h" #endif -#include "config/runtime_config.h" - #include "config/config.h" +#include "config/runtime_config.h" +#include "config/config_profile.h" #include "display.h" #include "scheduler.h" +extern profile_t *currentProfile; + controlRateConfig_t *getControlRateConfig(uint8_t profileIndex); #define MICROSECONDS_IN_A_SECOND (1000 * 1000) @@ -317,13 +320,26 @@ void showProfilePage(void) i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); - uint8_t currentRateProfileIndex = getCurrentControlRateProfile(); + static const char* const axisTitles[3] = {"ROL", "PIT", "YAW"}; + const pidProfile_t *pidProfile = ¤tProfile->pidProfile; + for (int axis = 0; axis < 3; ++axis) { + tfp_sprintf(lineBuffer, "%s P:%3d I:%3d D:%3d", + axisTitles[axis], + pidProfile->P8[axis], + pidProfile->I8[axis], + pidProfile->D8[axis] + ); + padLineBuffer(); + i2c_OLED_set_line(rowIndex++); + i2c_OLED_send_string(lineBuffer); + } + + const uint8_t currentRateProfileIndex = getCurrentControlRateProfile(); tfp_sprintf(lineBuffer, "Rate profile: %d", currentRateProfileIndex); i2c_OLED_set_line(rowIndex++); i2c_OLED_send_string(lineBuffer); - controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex); - + const controlRateConfig_t *controlRateConfig = getControlRateConfig(currentRateProfileIndex); tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d", controlRateConfig->rcExpo8, controlRateConfig->rcRate8 diff --git a/src/main/io/display.h b/src/main/io/display.h index 7d420b6563..8149a35ade 100644 --- a/src/main/io/display.h +++ b/src/main/io/display.h @@ -15,7 +15,7 @@ * along with Cleanflight. If not, see . */ -//#define ENABLE_DEBUG_OLED_PAGE +#define ENABLE_DEBUG_OLED_PAGE typedef enum { PAGE_WELCOME, diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 3f0bb134dc..6073285985 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -26,6 +26,7 @@ #include "platform.h" #include "scheduler.h" #include "version.h" +#include "debug.h" #include "build_config.h" @@ -426,14 +427,15 @@ static const char * const lookupTableMagHardware[] = { "AK8963" }; -static const char * const lookupTableDebug[] = { +static const char * const lookupTableDebug[DEBUG_COUNT] = { "NONE", "CYCLETIME", "BATTERY", "GYRO", "ACCELEROMETER", "MIXER", - "AIRMODE" + "AIRMODE", + "PIDLOOP", }; static const char * const lookupTableSuperExpoYaw[] = { diff --git a/src/main/mw.c b/src/main/mw.c index ae407cf710..682ea6c181 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -504,7 +504,6 @@ void processRx(void) } else { pidResetErrorGyroState(RESET_ITERM_AND_REDUCE_PID); } - pidResetErrorAngle(); } } else { pidResetErrorGyroState(RESET_DISABLE); @@ -655,6 +654,7 @@ void processRx(void) void subTaskPidController(void) { + const uint32_t startTime = micros(); // PID - note this is function pointer set by setPIDController() pid_controller( ¤tProfile->pidProfile, @@ -663,10 +663,13 @@ void subTaskPidController(void) &masterConfig.accelerometerTrims, &masterConfig.rxConfig ); + if (debugMode == DEBUG_PIDLOOP) {debug[2] = micros() - startTime;} } void subTaskMainSubprocesses(void) { + const uint32_t startTime = micros(); + if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) { filterRc(); } @@ -730,16 +733,18 @@ void subTaskMainSubprocesses(void) { #ifdef TRANSPONDER updateTransponder(); #endif + if (debugMode == DEBUG_PIDLOOP) {debug[1] = micros() - startTime;} } void subTaskMotorUpdate(void) { + const uint32_t startTime = micros(); if (debugMode == DEBUG_CYCLETIME) { static uint32_t previousMotorUpdateTime; - uint32_t currentDeltaTime = micros() - previousMotorUpdateTime; + const uint32_t currentDeltaTime = startTime - previousMotorUpdateTime; debug[2] = currentDeltaTime; debug[3] = currentDeltaTime - targetPidLooptime; - previousMotorUpdateTime = micros(); + previousMotorUpdateTime = startTime; } mixTable(); @@ -752,6 +757,7 @@ void subTaskMotorUpdate(void) if (motorControlEnable) { writeMotors(); } + if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;} } uint8_t setPidUpdateCountDown(void) { @@ -778,10 +784,12 @@ void taskMainPidLoopCheck(void) debug[1] = averageSystemLoadPercent; } + const uint32_t startTime = micros(); while (true) { if (gyroSyncCheckUpdate() || ((currentDeltaTime + (micros() - previousTime)) >= (targetLooptime + GYRO_WATCHDOG_DELAY))) { static uint8_t pidUpdateCountdown; + if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting if (runTaskMainSubprocesses) { subTaskMainSubprocesses(); runTaskMainSubprocesses = false; diff --git a/src/main/scheduler.h b/src/main/scheduler.h index 34141fd820..237776c259 100755 --- a/src/main/scheduler.h +++ b/src/main/scheduler.h @@ -44,14 +44,14 @@ typedef enum { /* Actual tasks */ TASK_SYSTEM = 0, TASK_GYROPID, - TASK_ATTITUDE, TASK_ACCEL, + TASK_ATTITUDE, + TASK_RX, TASK_SERIAL, + TASK_BATTERY, #ifdef BEEPER TASK_BEEPER, #endif - TASK_BATTERY, - TASK_RX, #ifdef GPS TASK_GPS, #endif diff --git a/src/main/scheduler_tasks.c b/src/main/scheduler_tasks.c index 223eadc03d..b9babb4b33 100644 --- a/src/main/scheduler_tasks.c +++ b/src/main/scheduler_tasks.c @@ -22,14 +22,15 @@ #include #include "scheduler.h" +void taskSystem(void); void taskMainPidLoopCheck(void); void taskUpdateAccelerometer(void); -void taskHandleSerial(void); void taskUpdateAttitude(void); -void taskUpdateBeeper(void); -void taskUpdateBattery(void); bool taskUpdateRxCheck(uint32_t currentDeltaTime); void taskUpdateRxMain(void); +void taskHandleSerial(void); +void taskUpdateBattery(void); +void taskUpdateBeeper(void); void taskProcessGPS(void); void taskUpdateCompass(void); void taskUpdateBaro(void); @@ -39,7 +40,6 @@ void taskUpdateDisplay(void); void taskTelemetry(void); void taskLedStrip(void); void taskTransponder(void); -void taskSystem(void); #ifdef USE_BST void taskBstReadWrite(void); void taskBstMasterProcess(void); @@ -61,13 +61,6 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_REALTIME, }, - [TASK_ATTITUDE] = { - .taskName = "ATTITUDE", - .taskFunc = taskUpdateAttitude, - .desiredPeriod = 1000000 / 100, - .staticPriority = TASK_PRIORITY_MEDIUM, - }, - [TASK_ACCEL] = { .taskName = "ACCEL", .taskFunc = taskUpdateAccelerometer, @@ -75,6 +68,21 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_MEDIUM, }, + [TASK_ATTITUDE] = { + .taskName = "ATTITUDE", + .taskFunc = taskUpdateAttitude, + .desiredPeriod = 1000000 / 100, + .staticPriority = TASK_PRIORITY_MEDIUM, + }, + + [TASK_RX] = { + .taskName = "RX", + .checkFunc = taskUpdateRxCheck, + .taskFunc = taskUpdateRxMain, + .desiredPeriod = 1000000 / 50, // If event-based scheduling doesn't work, fallback to periodic scheduling + .staticPriority = TASK_PRIORITY_HIGH, + }, + [TASK_SERIAL] = { .taskName = "SERIAL", .taskFunc = taskHandleSerial, @@ -82,6 +90,13 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_LOW, }, + [TASK_BATTERY] = { + .taskName = "BATTERY", + .taskFunc = taskUpdateBattery, + .desiredPeriod = 1000000 / 50, // 50 Hz + .staticPriority = TASK_PRIORITY_LOW, + }, + #ifdef BEEPER [TASK_BEEPER] = { .taskName = "BEEPER", @@ -91,21 +106,6 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif - [TASK_BATTERY] = { - .taskName = "BATTERY", - .taskFunc = taskUpdateBattery, - .desiredPeriod = 1000000 / 50, // 50 Hz - .staticPriority = TASK_PRIORITY_LOW, - }, - - [TASK_RX] = { - .taskName = "RX", - .checkFunc = taskUpdateRxCheck, - .taskFunc = taskUpdateRxMain, - .desiredPeriod = 1000000 / 50, // If event-based scheduling doesn't work, fallback to periodic scheduling - .staticPriority = TASK_PRIORITY_HIGH, - }, - #ifdef GPS [TASK_GPS] = { .taskName = "GPS", diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index caf6e7b880..312f692234 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -71,10 +71,6 @@ #define MAG #define USE_MAG_HMC5883 -#define INVERTER -#define BEEPER -#define DISPLAY - #define USE_VCP #define USE_USART1 #define USE_USART3 @@ -117,28 +113,26 @@ #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER -#define BLACKBOX -#define TELEMETRY -#define SERIAL_RX -#define SONAR -#define USE_SERVOS -#define USE_CLI - -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - - -#undef DISPLAY -#undef SONAR -//#if defined(OPBL) && defined(USE_SERIAL_1WIRE) -#undef BARO -//#undef BLACKBOX -#undef GPS -//#endif -#define SKIP_CLI_COMMAND_HELP - #define SPEKTRUM_BIND // USART3, PB11 (Flexport) #define BIND_PORT GPIOB #define BIND_PIN Pin_11 -#define USE_QUATERNION +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define INVERTER +#define BEEPER +#define DISPLAY +#define BLACKBOX +#define TELEMETRY +#define SERIAL_RX +#define USE_SERVOS +#define USE_CLI +//#define SONAR +//#define GPS + +#undef BARO + +#define SKIP_CLI_COMMAND_HELP +#define SKIP_PID_LUXFLOAT + From 6af2b8429787a596e47489e8923cdad962187942 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Thu, 5 May 2016 16:05:42 +0200 Subject: [PATCH 29/85] Inrease Max yaw P limit // filter defaults --- src/main/config/config.c | 2 +- src/main/flight/pid.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index d8d2f8c5a1..8b389fb2a1 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -403,7 +403,7 @@ static void resetConf(void) masterConfig.dcm_ki = 0; // 0.003 * 10000 masterConfig.gyro_lpf = 0; // 256HZ default masterConfig.gyro_sync_denom = 4; - masterConfig.gyro_soft_lpf_hz = 90; + masterConfig.gyro_soft_lpf_hz = 100; masterConfig.pid_process_denom = 2; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 3738f97633..9043e1e7bb 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -20,7 +20,7 @@ #define GYRO_I_MAX 256 // Gyro I limiter #define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter -#define YAW_P_LIMIT_MAX 400 // Maximum value for yaw P limiter +#define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter #define ITERM_RESET_THRESHOLD 15 #define DYNAMIC_PTERM_STICK_THRESHOLD 400 From 876fe536e6120551f82401eca5a444ab5e784bbc Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 5 May 2016 15:19:50 +0100 Subject: [PATCH 30/85] Fixed CC3D related build flags. --- Makefile | 3 +++ src/main/drivers/pwm_mapping.h | 6 +++--- src/main/target/CC3D/target.h | 6 +++++- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/Makefile b/Makefile index d5bfb1d006..4763aa787f 100644 --- a/Makefile +++ b/Makefile @@ -255,6 +255,9 @@ endif ifeq ($(TARGET),$(filter $(TARGET), $(CC3D_TARGETS))) TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D +ifeq ($(TARGET),CC3D_OPBL) +TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D_OPBL +endif TARGET_DIR = $(ROOT)/src/main/target/CC3D endif diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 9d8377f17c..ec8e05ce3c 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -70,11 +70,11 @@ typedef struct drv_pwm_config_s { #ifdef USE_SERVOS bool useServos; bool useChannelForwarding; // configure additional channels as servos -#ifdef CC3D - bool useBuzzerP6; -#endif uint16_t servoPwmRate; uint16_t servoCenterPulse; +#endif +#ifdef CC3D + bool useBuzzerP6; #endif bool airplane; // fixed wing hardware config, lots of servos etc uint16_t motorPwmRate; diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 312f692234..976b8f234e 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -128,11 +128,15 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI -//#define SONAR +#define SONAR //#define GPS #undef BARO +#ifdef CC3D_OPBL #define SKIP_CLI_COMMAND_HELP #define SKIP_PID_LUXFLOAT +#undef SONAR +#undef GPS +#endif From 7dbab96d99bc04b7b2b03e4431f33bd8269b7ec4 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Fri, 6 May 2016 00:17:44 +0200 Subject: [PATCH 31/85] Improve Expo Precision --- src/main/io/rc_curves.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/io/rc_curves.h b/src/main/io/rc_curves.h index f79b505992..0b3117991e 100644 --- a/src/main/io/rc_curves.h +++ b/src/main/io/rc_curves.h @@ -17,9 +17,9 @@ #pragma once -#define PITCH_LOOKUP_LENGTH 7 -#define YAW_LOOKUP_LENGTH 7 -#define THROTTLE_LOOKUP_LENGTH 12 +#define PITCH_LOOKUP_LENGTH 25 +#define YAW_LOOKUP_LENGTH 25 +#define THROTTLE_LOOKUP_LENGTH 16 extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL extern int16_t lookupYawRC[YAW_LOOKUP_LENGTH]; // lookup table for expo & RC rate YAW extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE From a959e6aa27b7eed1e6d113b3cf2b82f706e69bba Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 5 May 2016 23:39:14 +0100 Subject: [PATCH 32/85] Changed default CC3D_OPBL build to include pid_luxfloat. --- src/main/target/CC3D/target.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 976b8f234e..ca94199b8f 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -135,7 +135,8 @@ #ifdef CC3D_OPBL #define SKIP_CLI_COMMAND_HELP -#define SKIP_PID_LUXFLOAT +//#define SKIP_PID_LUXFLOAT +#undef DISPLAY #undef SONAR #undef GPS #endif From 88683a4da3c9b29a4643d69563ee84a4537f4a78 Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Wed, 4 May 2016 17:56:58 -0500 Subject: [PATCH 33/85] Setting gyro scale for fake sensors. --- src/main/sensors/initialisation.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 85b5ebb307..7e05f9688a 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -240,6 +240,7 @@ bool fakeGyroDetect(gyro_t *gyro) gyro->init = fakeGyroInit; gyro->read = fakeGyroRead; gyro->temperature = fakeGyroReadTemp; + gyro->scale = 1.0f / 16.4f; return true; } #endif From f46f50c223d80d19818e493b37314047431d548c Mon Sep 17 00:00:00 2001 From: JOhn Aughey Date: Fri, 6 May 2016 10:40:17 -0500 Subject: [PATCH 34/85] Before resetting, clear the reboot schedule flag. --- src/main/io/serial_msp.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index d44dc8e9aa..72a47a163d 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1861,6 +1861,10 @@ void mspProcess(void) waitForSerialPortToFinishTransmitting(candidatePort->port); stopMotors(); handleOneshotFeatureChangeOnRestart(); + // On real flight controllers, systemReset() will do a soft reset of the device, + // reloading the program. But to support offline testing this flag needs to be + // cleared so that the software doesn't continuously attempt to reboot itself. + isRebootScheduled = false; systemReset(); } } From 0af66353a4b324c8202527adcce8039b4b7a4cb6 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Fri, 6 May 2016 20:34:53 +0200 Subject: [PATCH 35/85] Working Fix for increased Expo precision by factor 5 --- src/main/io/rc_curves.c | 14 ++++++++++---- src/main/io/rc_curves.h | 6 +++--- src/main/mw.c | 8 ++++---- 3 files changed, 17 insertions(+), 11 deletions(-) diff --git a/src/main/io/rc_curves.c b/src/main/io/rc_curves.c index e6abf1d86c..c9684e2fba 100644 --- a/src/main/io/rc_curves.c +++ b/src/main/io/rc_curves.c @@ -34,17 +34,23 @@ int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & m void generatePitchRollCurve(controlRateConfig_t *controlRateConfig) { uint8_t i; + float j = 0; - for (i = 0; i < PITCH_LOOKUP_LENGTH; i++) - lookupPitchRollRC[i] = (2500 + controlRateConfig->rcExpo8 * (i * i - 25)) * i * (int32_t) controlRateConfig->rcRate8 / 2500; + for (i = 0; i < PITCH_LOOKUP_LENGTH; i++) { + lookupPitchRollRC[i] = (2500 + controlRateConfig->rcExpo8 * (j * j - 25)) * j * (int32_t) controlRateConfig->rcRate8 / 2500; + j += 0.2f; + } } void generateYawCurve(controlRateConfig_t *controlRateConfig) { uint8_t i; + float j = 0; - for (i = 0; i < YAW_LOOKUP_LENGTH; i++) - lookupYawRC[i] = (2500 + controlRateConfig->rcYawExpo8 * (i * i - 25)) * i / 25; + for (i = 0; i < YAW_LOOKUP_LENGTH; i++) { + lookupYawRC[i] = (2500 + controlRateConfig->rcYawExpo8 * (j * j - 25)) * j / 25; + j += 0.2f; + } } void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig) diff --git a/src/main/io/rc_curves.h b/src/main/io/rc_curves.h index 0b3117991e..21d6cdb360 100644 --- a/src/main/io/rc_curves.h +++ b/src/main/io/rc_curves.h @@ -17,9 +17,9 @@ #pragma once -#define PITCH_LOOKUP_LENGTH 25 -#define YAW_LOOKUP_LENGTH 25 -#define THROTTLE_LOOKUP_LENGTH 16 +#define PITCH_LOOKUP_LENGTH 31 +#define YAW_LOOKUP_LENGTH 31 +#define THROTTLE_LOOKUP_LENGTH 12 extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL extern int16_t lookupYawRC[YAW_LOOKUP_LENGTH]; // lookup table for expo & RC rate YAW extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE diff --git a/src/main/mw.c b/src/main/mw.c index ae407cf710..204ad70ebc 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -247,8 +247,8 @@ void annexCode(void) } } - tmp2 = tmp / 100; - rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 100) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 100; + tmp2 = tmp / 20; + rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 20) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 20; } else if (axis == YAW) { if (masterConfig.rcControlsConfig.yaw_deadband) { if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { @@ -257,8 +257,8 @@ void annexCode(void) tmp = 0; } } - tmp2 = tmp / 100; - rcCommand[axis] = (lookupYawRC[tmp2] + (tmp - tmp2 * 100) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 100) * -masterConfig.yaw_control_direction; + tmp2 = tmp / 20; + rcCommand[axis] = (lookupYawRC[tmp2] + (tmp - tmp2 * 20) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 20) * -masterConfig.yaw_control_direction; } // non coupled PID reduction scaler used in PID controller 1 and PID controller 2. From 9e5c5e88c7ad81f6d55be92dee1c0caa2e60b371 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Sat, 7 May 2016 00:51:25 +0200 Subject: [PATCH 36/85] Rework Fast PWM protocol configuration and timing --- src/main/config/config.c | 13 +++----- src/main/config/config_master.h | 4 +-- src/main/drivers/pwm_mapping.c | 15 +++------ src/main/drivers/pwm_mapping.h | 10 +++--- src/main/drivers/pwm_output.c | 55 +++++++++++++-------------------- src/main/drivers/pwm_output.h | 6 ++++ src/main/flight/mixer.c | 6 ++-- src/main/flight/mixer.h | 2 +- src/main/io/serial_cli.c | 14 ++++++--- src/main/io/serial_msp.c | 3 +- src/main/main.c | 14 +++------ src/main/mw.c | 2 +- 12 files changed, 67 insertions(+), 77 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index dc7abfa8a7..d3759bdd34 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -140,7 +140,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 134; +static const uint8_t EEPROM_CONF_VERSION = 135; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -190,8 +190,6 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->dterm_lpf_hz = 80; // filtering ON by default pidProfile->dynamic_pterm = 1; - pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes - #ifdef GTUNE pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune. pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune. @@ -485,7 +483,8 @@ static void resetConf(void) masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; #endif masterConfig.servo_pwm_rate = 50; - masterConfig.use_oneshot42 = 0; + masterConfig.fast_pwm_protocol = 0; + masterConfig.use_unsyncedPwm = 0; #ifdef CC3D masterConfig.use_buzzer_p6 = 0; #endif @@ -500,11 +499,7 @@ static void resetConf(void) resetSerialConfig(&masterConfig.serialConfig); -#if defined(STM32F10X) && !defined(CC3D) - masterConfig.emf_avoidance = 1; -#else - masterConfig.emf_avoidance = 0; -#endif + masterConfig.emf_avoidance = 0; // TODO - needs removal resetPidProfile(¤tProfile->pidProfile); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 281a7fa3d5..25a21afba7 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -34,8 +34,8 @@ typedef struct master_t { uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) - uint8_t use_oneshot42; // Oneshot42 - uint8_t use_multiShot; // multishot + uint8_t fast_pwm_protocol; // Fast Pwm Protocol + uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop #ifdef USE_SERVOS servoMixer_t customServoMixer[MAX_SERVO_RULES]; diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 9c53863270..0ce82b5184 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -31,8 +31,7 @@ void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); -void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t useOneshot42); -void pwmMultiShotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex); +void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint8_t useUnsyncedPwm, uint16_t idlePulse); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); /* @@ -912,7 +911,7 @@ if (init->useBuzzerP6) { if (type == MAP_TO_PPM_INPUT) { #if defined(SPARKY) || defined(ALIENFLIGHTF3) - if (init->useOneshot || isMotorBrushed(init->motorPwmRate)) { + if (init->useFastPwm || isMotorBrushed(init->motorPwmRate)) { ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2); } #endif @@ -923,18 +922,14 @@ if (init->useBuzzerP6) { } else if (type == MAP_TO_MOTOR_OUTPUT) { #ifdef CC3D - if (init->useOneshot || isMotorBrushed(init->motorPwmRate)){ + if (init->useFastPwm || isMotorBrushed(init->motorPwmRate)){ // Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed if (timerHardwarePtr->tim == TIM2) continue; } #endif - if (init->useOneshot) { - if (init->useMultiShot) { - pwmMultiShotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount); - } else { - pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->useOneshot42); - } + if (init->useFastPwm) { + pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->fastPwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; } else if (isMotorBrushed(init->motorPwmRate)) { pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index ec8e05ce3c..1edf1458d3 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -36,9 +36,11 @@ #define MAX_INPUTS 8 #define PWM_TIMER_MHZ 1 -#define ONESHOT_TIMER_MHZ 24 + #define PWM_BRUSHED_TIMER_MHZ 8 #define MULTISHOT_TIMER_MHZ 12 +#define ONESHOT42_TIMER_MHZ 24 +#define ONESHOT125_TIMER_MHZ 8 typedef struct sonarGPIOConfig_s { GPIO_TypeDef *gpio; @@ -59,9 +61,8 @@ typedef struct drv_pwm_config_s { bool useUART3; #endif bool useVbat; - bool useOneshot; - bool useOneshot42; - bool useMultiShot; + bool useFastPwm; + bool useUnsyncedPwm; bool useSoftSerial; bool useLEDStrip; #ifdef SONAR @@ -70,6 +71,7 @@ typedef struct drv_pwm_config_s { #ifdef USE_SERVOS bool useServos; bool useChannelForwarding; // configure additional channels as servos + uint8_t fastPwmProtocolType; uint16_t servoPwmRate; uint16_t servoCenterPulse; #endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 97a8fef655..56759cbd4b 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -135,27 +135,6 @@ static void pwmWriteStandard(uint8_t index, uint16_t value) { *motors[index]->ccr = value; } -#if defined(STM32F10X) && !defined(CC3D) -static void pwmWriteOneshot125(uint8_t index, uint16_t value) -{ - *motors[index]->ccr = value * 21 / 6; // 24Mhz -> 8Mhz -} - -static void pwmWriteOneshot42(uint8_t index, uint16_t value) -{ - *motors[index]->ccr = value * 7 / 6; -} -#else -static void pwmWriteOneshot125(uint8_t index, uint16_t value) -{ - *motors[index]->ccr = value * 3; // 24Mhz -> 8Mhz -} - -static void pwmWriteOneshot42(uint8_t index, uint16_t value) -{ - *motors[index]->ccr = value; -} -#endif static void pwmWriteMultiShot(uint8_t index, uint16_t value) { @@ -227,20 +206,30 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor motors[motorIndex]->pwmWritePtr = pwmWriteStandard; } -void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t useOneshot42) +void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint8_t useUnsyncedPwm, uint16_t idlePulse) { - motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT_TIMER_MHZ, 0xFFFF, 0); - if (useOneshot42) { - motors[motorIndex]->pwmWritePtr = pwmWriteOneshot42; - } else { - motors[motorIndex]->pwmWritePtr = pwmWriteOneshot125; - } -} + uint32_t timerMhzCounter; -void pwmMultiShotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex) -{ - motors[motorIndex] = pwmOutConfig(timerHardware, MULTISHOT_TIMER_MHZ, 0xFFFF, 0); - motors[motorIndex]->pwmWritePtr = pwmWriteMultiShot; + switch (fastPwmProtocolType) { + default: + case (PWM_TYPE_ONESHOT125): + timerMhzCounter = ONESHOT125_TIMER_MHZ; + break; + case (PWM_TYPE_ONESHOT42): + timerMhzCounter = ONESHOT42_TIMER_MHZ; + break; + case (PWM_TYPE_MULTISHOT): + timerMhzCounter = MULTISHOT_TIMER_MHZ; + } + + if (useUnsyncedPwm) { + uint32_t hz = timerMhzCounter * 1000000; + motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse); + } else { + motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0); + } + + motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot : pwmWriteStandard; } #ifdef USE_SERVOS diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 11036d5278..615ffa7ac2 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -17,6 +17,12 @@ #pragma once +typedef enum { + PWM_TYPE_ONESHOT125 = 0, + PWM_TYPE_ONESHOT42 = 1, + PWM_TYPE_MULTISHOT = 2 +} FastPwmProtocolTypes_e; + void pwmWriteMotor(uint8_t index, uint16_t value); void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmCompleteOneshotMotorUpdate(uint8_t motorCount); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 6240d85532..17717247c4 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -633,7 +633,7 @@ void writeServos(void) } #endif -void writeMotors(void) +void writeMotors(uint8_t unsyncedPwm) { uint8_t i; @@ -641,7 +641,7 @@ void writeMotors(void) pwmWriteMotor(i, motor[i]); - if (feature(FEATURE_ONESHOT125)) { + if (feature(FEATURE_ONESHOT125) && !unsyncedPwm) { pwmCompleteOneshotMotorUpdate(motorCount); } } @@ -653,7 +653,7 @@ void writeAllMotors(int16_t mc) // Sends commands to all motors for (i = 0; i < motorCount; i++) motor[i] = mc; - writeMotors(); + writeMotors(1); } void stopMotors(void) diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 36dca92263..50cb3eb1cd 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -218,6 +218,6 @@ int servoDirection(int servoIndex, int fromChannel); #endif void mixerResetDisarmedMotors(void); void mixTable(void); -void writeMotors(void); +void writeMotors(uint8_t unsyncedPwm); void stopMotors(void); void StopPwmAllMotors(void); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 6073285985..423c59bc4e 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -442,6 +442,10 @@ static const char * const lookupTableSuperExpoYaw[] = { "OFF", "ON", "ALWAYS" }; +static const char * const lookupTableFastPwm[] = { + "ONESHOT125", "ONESHOT42", "MULTISHOT" +}; + typedef struct lookupTableEntry_s { const char * const *values; const uint8_t valueCount; @@ -468,6 +472,7 @@ typedef enum { TABLE_MAG_HARDWARE, TABLE_DEBUG, TABLE_SUPEREXPO_YAW, + TABLE_FAST_PWM, } lookupTableIndex_e; static const lookupTableEntry_t lookupTables[] = { @@ -490,7 +495,8 @@ static const lookupTableEntry_t lookupTables[] = { { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) }, { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) }, { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) }, - { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) } + { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }, + { lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) }, }; #define VALUE_TYPE_OFFSET 0 @@ -566,12 +572,12 @@ const clivalue_t valueTable[] = { { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, - { "use_oneshot42", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_oneshot42, .config.lookup = { TABLE_OFF_ON } }, - { "use_multishot", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_multiShot, .config.lookup = { TABLE_OFF_ON } }, + { "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } }, + { "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.fast_pwm_protocol, .config.lookup = { TABLE_FAST_PWM } }, #ifdef CC3D { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } }, #endif - { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 300, 32000 } }, + { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } }, { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } }, { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } }, diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 72a47a163d..aa0d23b8c5 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -172,7 +172,8 @@ void setGyroSamplingSpeed(uint16_t looptime) { } #endif - if (!(masterConfig.use_multiShot || masterConfig.use_oneshot42) && ((masterConfig.gyro_sync_denom * gyroSampleRate) == 125)) masterConfig.pid_process_denom = 3; + // Oneshot125 protection + if ((masterConfig.fast_pwm_protocol == 0) && ((masterConfig.gyro_sync_denom * gyroSampleRate) == 125) && masterConfig.pid_process_denom < 3) masterConfig.pid_process_denom = 3; } } diff --git a/src/main/main.c b/src/main/main.c index ab02994433..06a7e99c3f 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -176,7 +176,7 @@ void init(void) #ifdef STM32F10X // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers // Configure the Flash Latency cycles and enable prefetch buffer - SetSysClock(masterConfig.emf_avoidance); + SetSysClock(0); // TODO - Remove from config in the future #endif //i2cSetOverclock(masterConfig.i2c_overclock); @@ -311,18 +311,14 @@ void init(void) pwm_params.servoPwmRate = masterConfig.servo_pwm_rate; #endif - pwm_params.useOneshot = feature(FEATURE_ONESHOT125); - if (masterConfig.use_oneshot42) { - pwm_params.useOneshot42 = masterConfig.use_oneshot42 ? true : false; - masterConfig.use_multiShot = false; - } else { - pwm_params.useMultiShot = masterConfig.use_multiShot ? true : false; - } + pwm_params.useFastPwm = feature(FEATURE_ONESHOT125); // Configurator feature abused for enabling Fast PWM + pwm_params.fastPwmProtocolType = masterConfig.fast_pwm_protocol; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; + pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm; if (feature(FEATURE_3D)) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; - if (pwm_params.motorPwmRate > 500) + if (pwm_params.motorPwmRate > 500 && !pwm_params.useFastPwm) pwm_params.idlePulse = 0; // brushed motors #ifdef CC3D pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false; diff --git a/src/main/mw.c b/src/main/mw.c index 9f226d1531..59ba692fc6 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -755,7 +755,7 @@ void subTaskMotorUpdate(void) #endif if (motorControlEnable) { - writeMotors(); + writeMotors(masterConfig.use_unsyncedPwm); } if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;} } From 90bc67e2ccacaa64ee45e496c9440759f170250a Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 9 May 2016 13:12:48 +0200 Subject: [PATCH 37/85] Configurable Iterm Reset Offset --- src/main/blackbox/blackbox.c | 4 ++-- src/main/config/config.c | 1 + src/main/flight/pid.c | 10 +++++----- src/main/flight/pid.h | 9 ++++----- src/main/io/serial_cli.c | 1 + 5 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index a84b3768fb..882a3a0f14 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1296,8 +1296,8 @@ static bool blackboxWriteSysinfo() (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); break; case 40: - blackboxPrintfHeaderLine("H_sensitivity:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.H_sensitivity); + blackboxPrintfHeaderLine("iterm_reset_offset:%d", + masterConfig.profile[masterConfig.current_profile_index].pidProfile.itermResetOffset); break; case 41: blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); diff --git a/src/main/config/config.c b/src/main/config/config.c index d3759bdd34..1e0f4961ed 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -187,6 +187,7 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->rollPitchItermResetRate = 200; pidProfile->rollPitchItermResetAlways = 0; pidProfile->yawItermResetRate = 50; + pidProfile->itermResetOffset = 15; pidProfile->dterm_lpf_hz = 80; // filtering ON by default pidProfile->dynamic_pterm = 1; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 0a5cf87db5..85de0917ae 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -88,7 +88,7 @@ float calculateExpoPlus(int axis, rxConfig_t *rxConfig) { propFactor = 1.0f; } else { superExpoFactor = (axis == YAW) ? rxConfig->superExpoFactorYaw : rxConfig->superExpoFactor; - propFactor = 1.0f - ((superExpoFactor / 100.0f) * (ABS(rcCommand[axis]) / 500.0f)); + propFactor = constrainf(1.0f - ((superExpoFactor / 100.0f) * (ABS(rcCommand[axis]) / 500.0f)), 0.0f, 1.0f); } return propFactor; @@ -223,11 +223,11 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * pidProfile->I8[axis], -250.0f, 250.0f); if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) { - if (ABS(gyroRate / 4.1f) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -ITERM_RESET_THRESHOLD, ITERM_RESET_THRESHOLD); + if (ABS(gyroRate / 4.1f) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -pidProfile->itermResetOffset, pidProfile->itermResetOffset); } if (axis == YAW) { - if (ABS(gyroRate / 4.1f) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -ITERM_RESET_THRESHOLD, ITERM_RESET_THRESHOLD); + if (ABS(gyroRate / 4.1f) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -YAW_ITERM_RESET_OFFSET, YAW_ITERM_RESET_OFFSET); } if (antiWindupProtection || motorLimitReached) { @@ -364,11 +364,11 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13); if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) { - if (ABS(gyroRate *10 / 41) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -ITERM_RESET_THRESHOLD << 13, (int32_t) + ITERM_RESET_THRESHOLD << 13); + if (ABS(gyroRate *10 / 41) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -pidProfile->itermResetOffset << 13, (int32_t) + pidProfile->itermResetOffset << 13); } if (axis == YAW) { - if (ABS(gyroRate * 10 / 41) >= pidProfile->yawItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -ITERM_RESET_THRESHOLD << 13, (int32_t) + ITERM_RESET_THRESHOLD << 13); + if (ABS(gyroRate * 10 / 41) >= pidProfile->yawItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -YAW_ITERM_RESET_OFFSET << 13, (int32_t) + YAW_ITERM_RESET_OFFSET << 13); } if (antiWindupProtection || motorLimitReached) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 361ff9508d..cdb571c179 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -22,7 +22,7 @@ #define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter #define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter -#define ITERM_RESET_THRESHOLD 15 +#define YAW_ITERM_RESET_OFFSET 15 // May be made configurable in the future, but not really needed for yaw #define DYNAMIC_PTERM_STICK_THRESHOLD 400 typedef enum { @@ -71,10 +71,9 @@ typedef struct pidProfile_s { uint8_t I8[PID_ITEM_COUNT]; uint8_t D8[PID_ITEM_COUNT]; - uint8_t H_sensitivity; - - uint16_t dterm_lpf_hz; // Delta Filter in hz - uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy + uint8_t itermResetOffset; // Reset offset for Iterm + uint16_t dterm_lpf_hz; // Delta Filter in hz + uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy uint16_t rollPitchItermResetRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates uint8_t rollPitchItermResetAlways; // Reset Iterm also without SUPER EXPO uint16_t yawItermResetRate; // Experimental threshold for resetting iterm for yaw on certain rates diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 423c59bc4e..f30b86fb56 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -734,6 +734,7 @@ const clivalue_t valueTable[] = { { "iterm_always_reset", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } }, { "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } }, { "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } }, + { "iterm_reset_offset", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermResetOffset, .config.minmax = { 0, 100 } }, { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } }, From db4da776c54fa33a45c6b239821c561d3313cc2f Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 9 May 2016 10:40:07 +0100 Subject: [PATCH 38/85] Localised RC lookup into rc_curves.c --- src/main/io/rc_curves.c | 30 +++++++++++++++++++++++++++--- src/main/io/rc_curves.h | 12 +++++------- src/main/mw.c | 12 ++++-------- 3 files changed, 36 insertions(+), 18 deletions(-) diff --git a/src/main/io/rc_curves.c b/src/main/io/rc_curves.c index c9684e2fba..ac6e675790 100644 --- a/src/main/io/rc_curves.c +++ b/src/main/io/rc_curves.c @@ -26,9 +26,13 @@ #include "config/config.h" -int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL -int16_t lookupYawRC[YAW_LOOKUP_LENGTH]; // lookup table for expo & RC rate YAW -int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE +#define PITCH_LOOKUP_LENGTH 31 +#define YAW_LOOKUP_LENGTH 31 +#define THROTTLE_LOOKUP_LENGTH 12 + +static int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL +static int16_t lookupYawRC[YAW_LOOKUP_LENGTH]; // lookup table for expo & RC rate YAW +static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE void generatePitchRollCurve(controlRateConfig_t *controlRateConfig) @@ -69,3 +73,23 @@ void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoCo lookupThrottleRC[i] = minThrottle + (int32_t) (escAndServoConfig->maxthrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] } } + +int16_t rcLookupPitchRoll(int32_t tmp) +{ + const int32_t tmp2 = tmp / 20; + return lookupPitchRollRC[tmp2] + (tmp - tmp2 * 20) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 20; +} + +int16_t rcLookupYaw(int32_t tmp) +{ + const int32_t tmp2 = tmp / 20; + return lookupYawRC[tmp2] + (tmp - tmp2 * 20) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 20; +} + +int16_t rcLookupThrottle(int32_t tmp) +{ + const int32_t tmp2 = tmp / 100; + // [0;1000] -> expo -> [MINTHROTTLE;MAXTHROTTLE] + return lookupThrottleRC[tmp2] + (tmp - tmp2 * 100) * (lookupThrottleRC[tmp2 + 1] - lookupThrottleRC[tmp2]) / 100; +} + diff --git a/src/main/io/rc_curves.h b/src/main/io/rc_curves.h index 21d6cdb360..4134f0a319 100644 --- a/src/main/io/rc_curves.h +++ b/src/main/io/rc_curves.h @@ -17,13 +17,11 @@ #pragma once -#define PITCH_LOOKUP_LENGTH 31 -#define YAW_LOOKUP_LENGTH 31 -#define THROTTLE_LOOKUP_LENGTH 12 -extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL -extern int16_t lookupYawRC[YAW_LOOKUP_LENGTH]; // lookup table for expo & RC rate YAW -extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE - void generatePitchRollCurve(controlRateConfig_t *controlRateConfig); void generateYawCurve(controlRateConfig_t *controlRateConfig); void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig); + +int16_t rcLookupPitchRoll(int32_t tmp); +int16_t rcLookupYaw(int32_t tmp); +int16_t rcLookupThrottle(int32_t tmp); + diff --git a/src/main/mw.c b/src/main/mw.c index 59ba692fc6..ffeb863591 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -222,7 +222,7 @@ void scaleRcCommandToFpvCamAngle(void) { void annexCode(void) { - int32_t tmp, tmp2; + int32_t tmp; int32_t axis, prop; // PITCH & ROLL only dynamic PID adjustment, depending on throttle value @@ -246,9 +246,7 @@ void annexCode(void) tmp = 0; } } - - tmp2 = tmp / 20; - rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 20) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 20; + rcCommand[axis] = rcLookupPitchRoll(tmp); } else if (axis == YAW) { if (masterConfig.rcControlsConfig.yaw_deadband) { if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { @@ -257,8 +255,7 @@ void annexCode(void) tmp = 0; } } - tmp2 = tmp / 20; - rcCommand[axis] = (lookupYawRC[tmp2] + (tmp - tmp2 * 20) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 20) * -masterConfig.yaw_control_direction; + rcCommand[axis] = rcLookupYaw(tmp) * -masterConfig.yaw_control_direction; } // non coupled PID reduction scaler used in PID controller 1 and PID controller 2. @@ -275,8 +272,7 @@ void annexCode(void) tmp = constrain(rcData[THROTTLE], masterConfig.rxConfig.mincheck, PWM_RANGE_MAX); tmp = (uint32_t)(tmp - masterConfig.rxConfig.mincheck) * PWM_RANGE_MIN / (PWM_RANGE_MAX - masterConfig.rxConfig.mincheck); } - tmp2 = tmp / 100; - rcCommand[THROTTLE] = lookupThrottleRC[tmp2] + (tmp - tmp2 * 100) * (lookupThrottleRC[tmp2 + 1] - lookupThrottleRC[tmp2]) / 100; // [0;1000] -> expo -> [MINTHROTTLE;MAXTHROTTLE] + rcCommand[THROTTLE] = rcLookupThrottle(tmp); if (feature(FEATURE_3D) && IS_RC_MODE_ACTIVE(BOX3DDISABLESWITCH) && !failsafeIsActive()) { fix12_t throttleScaler = qConstruct(rcCommand[THROTTLE] - 1000, 1000); From 52b40b1028c6750e878b5a69fba921280e9aab8c Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 9 May 2016 11:00:11 +0100 Subject: [PATCH 39/85] Renamed annexCode to updateRcCommands and tidied. --- src/main/mw.c | 61 +++++++++++++++++++++++---------------------------- 1 file changed, 28 insertions(+), 33 deletions(-) diff --git a/src/main/mw.c b/src/main/mw.c index ffeb863591..8c07b4dc6b 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -220,12 +220,10 @@ void scaleRcCommandToFpvCamAngle(void) { rcCommand[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500); } -void annexCode(void) +static void updateRcCommands(void) { - int32_t tmp; - int32_t axis, prop; - // PITCH & ROLL only dynamic PID adjustment, depending on throttle value + int32_t prop; if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) { prop = 100; } else { @@ -236,35 +234,32 @@ void annexCode(void) } } - for (axis = 0; axis < 3; axis++) { - tmp = MIN(ABS(rcData[axis] - masterConfig.rxConfig.midrc), 500); - if (axis == ROLL || axis == PITCH) { - if (masterConfig.rcControlsConfig.deadband) { - if (tmp > masterConfig.rcControlsConfig.deadband) { - tmp -= masterConfig.rcControlsConfig.deadband; - } else { - tmp = 0; - } - } - rcCommand[axis] = rcLookupPitchRoll(tmp); - } else if (axis == YAW) { - if (masterConfig.rcControlsConfig.yaw_deadband) { - if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { - tmp -= masterConfig.rcControlsConfig.yaw_deadband; - } else { - tmp = 0; - } - } - rcCommand[axis] = rcLookupYaw(tmp) * -masterConfig.yaw_control_direction; - } - + for (int axis = 0; axis < 3; axis++) { // non coupled PID reduction scaler used in PID controller 1 and PID controller 2. PIDweight[axis] = prop; - if (rcData[axis] < masterConfig.rxConfig.midrc) + int32_t tmp = MIN(ABS(rcData[axis] - masterConfig.rxConfig.midrc), 500); + if (axis == ROLL || axis == PITCH) { + if (tmp > masterConfig.rcControlsConfig.deadband) { + tmp -= masterConfig.rcControlsConfig.deadband; + } else { + tmp = 0; + } + rcCommand[axis] = rcLookupPitchRoll(tmp); + } else if (axis == YAW) { + if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { + tmp -= masterConfig.rcControlsConfig.yaw_deadband; + } else { + tmp = 0; + } + rcCommand[axis] = rcLookupYaw(tmp) * -masterConfig.yaw_control_direction; + } + if (rcData[axis] < masterConfig.rxConfig.midrc) { rcCommand[axis] = -rcCommand[axis]; + } } + int32_t tmp; if (feature(FEATURE_3D)) { tmp = constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX); tmp = (uint32_t)(tmp - PWM_RANGE_MIN); @@ -280,10 +275,10 @@ void annexCode(void) } if (FLIGHT_MODE(HEADFREE_MODE)) { - float radDiff = degreesToRadians(DECIDEGREES_TO_DEGREES(attitude.values.yaw) - headFreeModeHold); - float cosDiff = cos_approx(radDiff); - float sinDiff = sin_approx(radDiff); - int16_t rcCommand_PITCH = rcCommand[PITCH] * cosDiff + rcCommand[ROLL] * sinDiff; + const float radDiff = degreesToRadians(DECIDEGREES_TO_DEGREES(attitude.values.yaw) - headFreeModeHold); + const float cosDiff = cos_approx(radDiff); + const float sinDiff = sin_approx(radDiff); + const int16_t rcCommand_PITCH = rcCommand[PITCH] * cosDiff + rcCommand[ROLL] * sinDiff; rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff; rcCommand[PITCH] = rcCommand_PITCH; } @@ -859,8 +854,8 @@ void taskUpdateRxMain(void) processRx(); isRXDataNew = true; - // the 'annexCode' initialses rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState - annexCode(); + // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState + updateRcCommands(); #ifdef BARO if (sensors(SENSOR_BARO)) { updateAltHoldState(); From a968669f91d0ccb71b0ff623c0c79c4709d73e0b Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 9 May 2016 16:01:44 +0100 Subject: [PATCH 40/85] Split off updateLEDs function from updateRcCommands. --- src/main/mw.c | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/src/main/mw.c b/src/main/mw.c index 8c07b4dc6b..bfb0a1a547 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -169,7 +169,8 @@ bool isCalibrating() return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete()); } -void filterRc(void){ +void filterRc(void) +{ static int16_t lastCommand[4] = { 0, 0, 0, 0 }; static int16_t deltaRC[4] = { 0, 0, 0, 0 }; static int16_t factor, rcInterpolationFactor; @@ -287,8 +288,10 @@ static void updateRcCommands(void) if (masterConfig.rxConfig.fpvCamAngleDegrees && !FLIGHT_MODE(HEADFREE_MODE)) { scaleRcCommandToFpvCamAngle(); } +} - +static void updateLEDs(void) +{ if (ARMING_FLAG(ARMED)) { LED0_ON; } else { @@ -313,10 +316,6 @@ static void updateRcCommands(void) warningLedUpdate(); } - - // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. - if (gyro.temperature) - gyro.temperature(&telemTemperature1); } void mwDisarm(void) @@ -665,6 +664,11 @@ void subTaskMainSubprocesses(void) { filterRc(); } + // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. + if (gyro.temperature) { + gyro.temperature(&telemTemperature1); + } + #ifdef MAG if (sensors(SENSOR_MAG)) { updateMagHold(); @@ -856,6 +860,8 @@ void taskUpdateRxMain(void) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); + updateLEDs(); + #ifdef BARO if (sensors(SENSOR_BARO)) { updateAltHoldState(); From 4e178629e055fa0076d196b346a7966e3383fa7b Mon Sep 17 00:00:00 2001 From: Michael Keller Date: Tue, 10 May 2016 11:16:00 +1200 Subject: [PATCH 41/85] Added commands to restore profile / rateprofile selection to output of 'dump all' CLI command. Also added command to save config to 'dump all' output. --- src/main/io/serial_cli.c | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index f30b86fb56..1ea06c9f0a 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -1977,8 +1977,16 @@ static void cliDump(char *cmdline) cliDumpRateProfile(rateCount); } + cliPrint("\r\n# restore original profile / rateprofile selection\r\n"); + changeProfile(activeProfile); + cliProfile(""); + printSectionBreak(); + changeControlRateProfile(currentRateIndex); + cliRateProfile(""); + + cliPrint("\r\n# save configuration\r\nsave\r\n"); } else { cliDumpProfile(masterConfig.current_profile_index); cliDumpRateProfile(currentProfile->activeRateProfile); @@ -2003,24 +2011,25 @@ void cliDumpProfile(uint8_t profileIndex) { cliPrint("\r\n# profile\r\n"); cliProfile(""); cliPrintf("############################# PROFILE VALUES ####################################\r\n"); - cliProfile(""); + printSectionBreak(); dumpValues(PROFILE_VALUE); cliRateProfile(""); } + void cliDumpRateProfile(uint8_t rateProfileIndex) { if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values return; changeControlRateProfile(rateProfileIndex); cliPrint("\r\n# rateprofile\r\n"); - cliRateProfile(""); + cliRateProfile(""); printSectionBreak(); dumpValues(PROFILE_RATE_VALUE); - } + void cliEnter(serialPort_t *serialPort) { cliMode = 1; @@ -2397,7 +2406,7 @@ static void cliRateProfile(char *cmdline) { i = atoi(cmdline); if (i >= 0 && i < MAX_RATEPROFILES) { changeControlRateProfile(i); - cliRateProfile(""); + cliRateProfile(""); } } } From 85ab270772cfbd3781f521770aaf729d79ca51a0 Mon Sep 17 00:00:00 2001 From: Gary Keeble Date: Tue, 10 May 2016 07:21:33 +0100 Subject: [PATCH 42/85] Add compile target name We might as well know what board was running beta flight. --- src/main/blackbox/blackbox.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 3f1a481403..ea43912a9f 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1133,7 +1133,7 @@ static bool blackboxWriteSysinfo() blackboxPrintfHeaderLine("Firmware type:Cleanflight"); break; case 1: - blackboxPrintfHeaderLine("Firmware revision:Betaflight %s (%s)", FC_VERSION_STRING, shortGitRevision); + blackboxPrintfHeaderLine("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName); break; case 2: blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime); From 8244990c863abb0447e20001861ff9c61dc13785 Mon Sep 17 00:00:00 2001 From: YANN OEFFNER Date: Tue, 10 May 2016 12:28:13 +0200 Subject: [PATCH 43/85] Clean IRCFUSIONF3 target --- Makefile | 11 +----- src/main/target/IRCFUSIONF3/target.h | 53 +++------------------------- 2 files changed, 5 insertions(+), 59 deletions(-) diff --git a/Makefile b/Makefile index d5bfb1d006..1c1e2ac263 100644 --- a/Makefile +++ b/Makefile @@ -719,17 +719,8 @@ IRCFUSIONF3_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ - drivers/barometer_ms5611.c \ - drivers/compass_ak8975.c \ drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.h \ drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c \ - drivers/sonar_hcsr04.c \ io/flashfs.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) @@ -773,7 +764,7 @@ MOTOLAB_SRC = \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ $(VCP_SRC) - + SPRACINGF3MINI_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/accgyro_mpu.c \ diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index ccc9fa9975..c3b99b5c76 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -19,26 +19,18 @@ #define TARGET_BOARD_IDENTIFIER "IFF3" +#define LED0 #define LED0_GPIO GPIOB #define LED0_PIN Pin_3 #define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB -#define BEEP_GPIO GPIOC -#define BEEP_PIN Pin_15 -#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC -#define BEEPER_INVERTED - #define USABLE_TIMER_CHANNEL_COUNT 17 -#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready +#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready, no MAG #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define USE_MAG_DATA_READY_SIGNAL -#define ENSURE_MAG_DATA_READY_IS_HIGH - - #define GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG @@ -48,27 +40,15 @@ #define ACC_MPU6050_ALIGN CW270_DEG #define BARO -#define USE_BARO_MS5611 #define USE_BARO_BMP085 -#define MAG -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define MAG_HMC5883_ALIGN CW270_DEG - #define USE_FLASHFS #define USE_FLASH_M25P16 -#define SONAR -#define BEEPER -#define LED0 - #define USE_USART1 #define USE_USART2 #define USE_USART3 -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 3 #ifndef UART1_GPIO #define UART1_TX_PIN GPIO_Pin_9 // PA9 @@ -95,13 +75,6 @@ #define UART3_RX_PINSOURCE GPIO_PinSource11 #endif -#define SOFTSERIAL_1_TIMER TIM3 -#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 -#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SOFTSERIAL_2_TIMER TIM3 -#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 -#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 - #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA @@ -132,29 +105,12 @@ #define RSSI_ADC_GPIO_PIN GPIO_Pin_2 #define RSSI_ADC_CHANNEL ADC_Channel_12 -#define LED_STRIP -#define LED_STRIP_TIMER TIM1 - -#define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 -#define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 -#define WS2811_DMA_CHANNEL DMA1_Channel2 -#define WS2811_IRQ DMA1_Channel2_IRQn -#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER - #define BLACKBOX -#define DISPLAY #define GPS //#define GTUNE #define SERIAL_RX -#define TELEMETRY #define USE_SERVOS +#define TELEMETRY #define USE_CLI #define SPEKTRUM_BIND @@ -180,4 +136,3 @@ #define S1W_RX_PIN GPIO_Pin_10 #endif - From 17e5c569b2f861745492d4c51341cec08865b6f3 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 11 May 2016 23:00:29 +0200 Subject: [PATCH 44/85] Optimal defaults --- src/main/config/config.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 1e0f4961ed..84c2c22679 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -183,12 +183,12 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->D8[PIDVEL] = 75; pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; - pidProfile->yaw_lpf_hz = 70; + pidProfile->yaw_lpf_hz = 80; pidProfile->rollPitchItermResetRate = 200; pidProfile->rollPitchItermResetAlways = 0; pidProfile->yawItermResetRate = 50; pidProfile->itermResetOffset = 15; - pidProfile->dterm_lpf_hz = 80; // filtering ON by default + pidProfile->dterm_lpf_hz = 110; // filtering ON by default pidProfile->dynamic_pterm = 1; #ifdef GTUNE From f3f7827c335b76bba2d6176c6f6d6cac8f6a430f Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 16 May 2016 21:26:06 +0200 Subject: [PATCH 45/85] Apply gyro zero before filtering // Fix Luxfloat Drift --- src/main/sensors/gyro.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 17981d5883..b22955cead 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -152,6 +152,12 @@ void gyroUpdate(void) alignSensors(gyroADC, gyroADC, gyroAlign); + if (!isGyroCalibrationComplete()) { + performAcclerationCalibration(gyroConfig->gyroMovementCalibrationThreshold); + } + + applyGyroZero(); + if (gyroLpfCutFreq) { if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */ @@ -162,10 +168,4 @@ void gyroUpdate(void) } } } - - if (!isGyroCalibrationComplete()) { - performAcclerationCalibration(gyroConfig->gyroMovementCalibrationThreshold); - } - - applyGyroZero(); } From 74cd38a77bf395ed8d18032bb63cf06bfa67cf57 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 16 May 2016 21:29:18 +0200 Subject: [PATCH 46/85] F1 default Loop set to 1khz --- src/main/config/config.c | 6 +++++- src/main/version.h | 2 +- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 84c2c22679..691d87c156 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -407,7 +407,11 @@ static void resetConf(void) masterConfig.dcm_kp = 2500; // 1.0 * 10000 masterConfig.dcm_ki = 0; // 0.003 * 10000 masterConfig.gyro_lpf = 0; // 256HZ default +#ifdef STM32F10X + masterConfig.gyro_sync_denom = 8; +#else masterConfig.gyro_sync_denom = 4; +#endif masterConfig.gyro_soft_lpf_hz = 100; masterConfig.pid_process_denom = 2; @@ -440,7 +444,7 @@ static void resetConf(void) masterConfig.rxConfig.spektrum_sat_bind = 0; masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; masterConfig.rxConfig.midrc = 1500; - masterConfig.rxConfig.mincheck = 1080; + masterConfig.rxConfig.mincheck = 1100; masterConfig.rxConfig.maxcheck = 1900; masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection diff --git a/src/main/version.h b/src/main/version.h index 922d94b1d7..009ff6e352 100644 --- a/src/main/version.h +++ b/src/main/version.h @@ -17,7 +17,7 @@ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) #define FC_VERSION_MINOR 7 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed +#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) From d6e7ed3560ac2abe73d768c0558e4f367e7e3608 Mon Sep 17 00:00:00 2001 From: Michael Keller Date: Mon, 18 Apr 2016 13:45:31 +1200 Subject: [PATCH 47/85] Added 'ledstrip_visual_beeper' feature. Added build condition for LED strip related config option. Added 'ledstrip_visual_beeper' feature. Added build condition for LED strip related config option. --- src/main/config/config.c | 1 + src/main/config/config_master.h | 1 + src/main/io/beeper.c | 8 ++++++++ src/main/io/beeper.h | 1 + src/main/io/ledstrip.c | 24 +++++++++++++++++++++++- src/main/io/serial_cli.c | 3 +++ 6 files changed, 37 insertions(+), 1 deletion(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 691d87c156..ed41b0a919 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -565,6 +565,7 @@ static void resetConf(void) #ifdef LED_STRIP applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT); applyDefaultLedStripConfig(masterConfig.ledConfigs); + masterConfig.ledstrip_visual_beeper = 0; #endif #ifdef SPRACINGF3 diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 25a21afba7..c61df40e60 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -119,6 +119,7 @@ typedef struct master_t { #ifdef LED_STRIP ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH]; hsvColor_t colors[CONFIGURABLE_COLOR_COUNT]; + uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on #endif #ifdef TRANSPONDER diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index e7ec349649..b4893a1f16 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -386,6 +386,13 @@ int beeperTableEntryCount(void) return (int)BEEPER_TABLE_ENTRY_COUNT; } +/* + * Returns true if the beeper is on, false otherwise + */ +bool isBeeperOn(void) { + return beeperIsOn; +} + #else // Stub out beeper functions if #BEEPER not defined @@ -397,5 +404,6 @@ uint32_t getArmingBeepTimeMicros(void) {return 0;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;} int beeperTableEntryCount(void) {return 0;} +bool isBeeperOn(void) {return false;} #endif diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 7d3ef38ef5..0f9f488ef6 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -53,3 +53,4 @@ uint32_t getArmingBeepTimeMicros(void); beeperMode_e beeperModeForTableIndex(int idx); const char *beeperNameForTableIndex(int idx); int beeperTableEntryCount(void); +bool isBeeperOn(void); diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index a52ed8df09..f0582a220d 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -34,19 +34,41 @@ #include "drivers/light_ws2811strip.h" #include "drivers/system.h" #include "drivers/serial.h" +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/gpio.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" #include +#include "common/axis.h" #include "io/rc_controls.h" #include "sensors/battery.h" +#include "sensors/sensors.h" +#include "sensors/boardalignment.h" +#include "sensors/gyro.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" #include "io/ledstrip.h" +#include "io/beeper.h" +#include "io/escservo.h" +#include "io/gimbal.h" +#include "io/serial.h" #include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" + +#include "telemetry/telemetry.h" #include "config/runtime_config.h" #include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" static bool ledStripInitialised = false; static bool ledStripEnabled = true; @@ -916,7 +938,7 @@ void updateLedStrip(void) return; } - if (IS_RC_MODE_ACTIVE(BOXLEDLOW)) { + if (IS_RC_MODE_ACTIVE(BOXLEDLOW) && !(masterConfig.ledstrip_visual_beeper && isBeeperOn())) { if (ledStripEnabled) { ledStripDisable(); ledStripEnabled = false; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 1ea06c9f0a..55f77bb595 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -771,6 +771,9 @@ const clivalue_t valueTable[] = { { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } }, { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } }, { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } }, +#ifdef LED_STRIP + { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } }, +#endif }; #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) From 03ef7f9ba981bcdd9087d068fc9a54393d918ec7 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 17 May 2016 08:45:33 +0100 Subject: [PATCH 48/85] Moved declaration of pidControllerFuncPtr into pid.h --- src/main/flight/pid.c | 21 ++++++++------------- src/main/flight/pid.h | 6 ++++++ src/main/mw.c | 3 --- src/main/sensors/acceleration.h | 2 +- 4 files changed, 15 insertions(+), 17 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 85de0917ae..58e04898f1 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -68,11 +68,8 @@ static float errorGyroIf[3], errorGyroIfLimit[3]; static bool lowThrottlePidReduction; -static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, - uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); - -typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, - uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype +static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, + uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig); pidControllerFuncPtr pid_controller = pidMultiWiiRewrite; // which pid controller are we using, defaultMultiWii @@ -80,7 +77,7 @@ void setTargetPidLooptime(uint8_t pidProcessDenom) { targetPidLooptime = targetLooptime * pidProcessDenom; } -float calculateExpoPlus(int axis, rxConfig_t *rxConfig) { +float calculateExpoPlus(int axis, const rxConfig_t *rxConfig) { float propFactor; float superExpoFactor; @@ -94,7 +91,7 @@ float calculateExpoPlus(int axis, rxConfig_t *rxConfig) { return propFactor; } -uint16_t getDynamicKp(int axis, pidProfile_t *pidProfile) { +uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) { uint16_t dynamicKp; uint32_t dynamicFactor = constrain(ABS(rcCommand[axis] << 8) / DYNAMIC_PTERM_STICK_THRESHOLD, 0, 1 << 7); @@ -136,8 +133,8 @@ static filterStatePt1_t deltaFilterState[3]; static filterStatePt1_t yawFilterState; #ifndef SKIP_PID_LUXFLOAT -static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, - uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) +static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, + uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig) { float RateError, AngleRate, gyroRate; float ITerm,PTerm,DTerm; @@ -277,11 +274,9 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa } #endif -static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, - rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) +static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, + const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig) { - UNUSED(rxConfig); - int axis; int32_t PTerm, ITerm, DTerm, delta; static int32_t lastRate[3]; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index cdb571c179..046adbcb66 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -90,6 +90,12 @@ typedef struct pidProfile_s { #endif } pidProfile_t; +struct controlRateConfig_s; +union rollAndPitchTrims_u; +struct rxConfig_s; +typedef void (*pidControllerFuncPtr)(const pidProfile_t *pidProfile, const struct controlRateConfig_s *controlRateConfig, + uint16_t max_angle_inclination, const union rollAndPitchTrims_u *angleTrim, const struct rxConfig_s *rxConfig); // pid controller function prototype + extern int16_t axisPID[XYZ_AXIS_COUNT]; extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; bool antiWindupProtection; diff --git a/src/main/mw.c b/src/main/mw.c index bfb0a1a547..b9da3e6b70 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -119,9 +119,6 @@ uint16_t filteredCycleTime; static bool isRXDataNew; static bool armingCalibrationWasInitialised; -typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, - uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype - extern pidControllerFuncPtr pid_controller; void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta) diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index d2d892fd6c..38006a04f9 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -45,7 +45,7 @@ typedef struct rollAndPitchTrims_s { int16_t pitch; } rollAndPitchTrims_t_def; -typedef union { +typedef union rollAndPitchTrims_u { int16_t raw[2]; rollAndPitchTrims_t_def values; } rollAndPitchTrims_t; From fc6298d1e9ebafe31c368ae0d0376b2727fc86c3 Mon Sep 17 00:00:00 2001 From: DTF UHF Date: Fri, 20 May 2016 12:27:01 -0400 Subject: [PATCH 49/85] Clean up Doge buzzer code and use correct logic. --- src/main/target/DOGE/target.h | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 9be5650a72..008557d335 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -37,12 +37,7 @@ #define BEEP_GPIO GPIOB #define BEEP_PIN Pin_2 #define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB -//#define BEEPER_INVERTED - -// #define BEEP_GPIO GPIOB -// #define BEEP_PIN Pin_13 -// #define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB -// #define BEEPER_INVERTED +#define BEEPER_INVERTED // tqfp48 pin 3 #define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOC From ff5c320b4a814e87893189bbc80566e58f142e84 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 23 May 2016 23:38:20 +0200 Subject: [PATCH 50/85] Iterm reset rework // Airmode Iterm Protection Configurable // Dynamic Ki New defaults --- src/main/blackbox/blackbox.c | 12 ++--- src/main/config/config.c | 17 ++++---- src/main/flight/mixer.c | 2 - src/main/flight/mixer.h | 1 - src/main/flight/pid.c | 85 +++++++++++++----------------------- src/main/flight/pid.h | 19 +++----- src/main/io/rc_controls.c | 9 ---- src/main/io/rc_controls.h | 1 - src/main/io/serial_cli.c | 9 ++-- src/main/mw.c | 30 +++++-------- src/main/rx/rx.h | 7 +-- src/main/version.h | 2 +- 12 files changed, 69 insertions(+), 125 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index ea43912a9f..97ca2b619e 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1280,24 +1280,24 @@ static bool blackboxWriteSysinfo() masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); break; case 36: - blackboxPrintfHeaderLine("dynamic_pterm:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pterm); + blackboxPrintfHeaderLine("dynamic_pid:%d", + masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); break; case 37: blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermResetRate); + masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); break; case 38: blackboxPrintfHeaderLine("yawItermResetRate:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermResetRate); + masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); break; case 39: blackboxPrintfHeaderLine("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); break; case 40: - blackboxPrintfHeaderLine("iterm_reset_offset:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.itermResetOffset); + blackboxPrintfHeaderLine("airmode_activate_throttle:%d", + masterConfig.rxConfig.airModeActivateThreshold); break; case 41: blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); diff --git a/src/main/config/config.c b/src/main/config/config.c index 691d87c156..63a2391821 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -140,7 +140,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 135; +static const uint8_t EEPROM_CONF_VERSION = 136; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -154,13 +154,13 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->pidController = 1; pidProfile->P8[ROLL] = 45; - pidProfile->I8[ROLL] = 35; + pidProfile->I8[ROLL] = 55; pidProfile->D8[ROLL] = 18; pidProfile->P8[PITCH] = 45; - pidProfile->I8[PITCH] = 35; + pidProfile->I8[PITCH] = 55; pidProfile->D8[PITCH] = 18; pidProfile->P8[YAW] = 90; - pidProfile->I8[YAW] = 40; + pidProfile->I8[YAW] = 50; pidProfile->D8[YAW] = 0; pidProfile->P8[PIDALT] = 50; pidProfile->I8[PIDALT] = 0; @@ -184,12 +184,10 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_lpf_hz = 80; - pidProfile->rollPitchItermResetRate = 200; - pidProfile->rollPitchItermResetAlways = 0; - pidProfile->yawItermResetRate = 50; - pidProfile->itermResetOffset = 15; + pidProfile->rollPitchItermIgnoreRate = 200; + pidProfile->yawItermIgnoreRate = 50;; pidProfile->dterm_lpf_hz = 110; // filtering ON by default - pidProfile->dynamic_pterm = 1; + pidProfile->dynamic_pid = 1; #ifdef GTUNE pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune. @@ -462,6 +460,7 @@ static void resetConf(void) masterConfig.rxConfig.fpvCamAngleDegrees = 0; masterConfig.rxConfig.max_aux_channel = 6; masterConfig.rxConfig.superExpoFactor = 30; + masterConfig.rxConfig.airModeActivateThreshold = 1350; masterConfig.rxConfig.superExpoFactorYaw = 30; masterConfig.rxConfig.superExpoYawMode = 0; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 17717247c4..c777ca39f7 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -822,7 +822,6 @@ void mixTable(void) throttleRange = throttleMax - throttleMin; if (rollPitchYawMixRange > throttleRange) { - motorLimitReached = true; mixReduction = qConstruct(throttleRange, rollPitchYawMixRange); for (i = 0; i < motorCount; i++) { @@ -833,7 +832,6 @@ void mixTable(void) if (debugMode == DEBUG_AIRMODE && i < 3) debug[1] = rollPitchYawMixRange; } else { - motorLimitReached = false; throttleMin = throttleMin + (rollPitchYawMixRange / 2); throttleMax = throttleMax - (rollPitchYawMixRange / 2); } diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 50cb3eb1cd..a1f79d5a8f 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -189,7 +189,6 @@ extern int16_t servo[MAX_SUPPORTED_SERVOS]; bool isMixerUsingServos(void); void writeServos(void); void filterServos(void); -bool motorLimitReached; #endif extern int16_t motor[MAX_SUPPORTED_MOTORS]; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 58e04898f1..7e2a346238 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -49,7 +49,6 @@ #include "config/runtime_config.h" extern uint8_t motorCount; -extern bool motorLimitReached; uint32_t targetPidLooptime; int16_t axisPID[3]; @@ -61,13 +60,11 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; // PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction uint8_t PIDweight[3]; -static int32_t errorGyroI[3], errorGyroILimit[3]; +static int32_t errorGyroI[3]; #ifndef SKIP_PID_LUXFLOAT -static float errorGyroIf[3], errorGyroIfLimit[3]; +static float errorGyroIf[3]; #endif -static bool lowThrottlePidReduction; - static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig); @@ -101,22 +98,28 @@ uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) { return dynamicKp; } -void pidResetErrorGyroState(uint8_t resetOption) -{ - if (resetOption >= RESET_ITERM) { - int axis; - for (axis = 0; axis < 3; axis++) { - errorGyroI[axis] = 0; -#ifndef SKIP_PID_LUXFLOAT - errorGyroIf[axis] = 0.0f; -#endif - } - } +uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile) { + uint16_t dynamicKi; + uint16_t resetRate; - if (resetOption == RESET_ITERM_AND_REDUCE_PID) { - lowThrottlePidReduction = true; - } else { - lowThrottlePidReduction = false; + resetRate = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate; + + uint32_t dynamicFactor = (1 << 8) - constrain(ABS(gyroADC[axis] << 8) / resetRate, 0, 1 << 8); + + dynamicKi = (pidProfile->I8[axis] * dynamicFactor) >> 8; + + return dynamicKi; +} + +void pidResetErrorGyroState(void) +{ + int axis; + + for (axis = 0; axis < 3; axis++) { + errorGyroI[axis] = 0; +#ifndef SKIP_PID_LUXFLOAT + errorGyroIf[axis] = 0.0f; +#endif } } @@ -202,7 +205,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // multiplication of rcCommand corresponds to changing the sticks scaling here RateError = AngleRate - gyroRate; - uint16_t kP = (pidProfile->dynamic_pterm) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; + uint16_t kP = (pidProfile->dynamic_pid) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; // -----calculate P component if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { @@ -217,21 +220,9 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ } // -----calculate I component. - errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * pidProfile->I8[axis], -250.0f, 250.0f); + uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile) : pidProfile->I8[axis]; - if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) { - if (ABS(gyroRate / 4.1f) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -pidProfile->itermResetOffset, pidProfile->itermResetOffset); - } - - if (axis == YAW) { - if (ABS(gyroRate / 4.1f) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = constrainf(errorGyroIf[axis], -YAW_ITERM_RESET_OFFSET, YAW_ITERM_RESET_OFFSET); - } - - if (antiWindupProtection || motorLimitReached) { - errorGyroIf[axis] = constrainf(errorGyroIf[axis], -errorGyroIfLimit[axis], errorGyroIfLimit[axis]); - } else { - errorGyroIfLimit[axis] = ABS(errorGyroIf[axis]); - } + errorGyroIf[axis] = constrainf(kI + luxITermScale * RateError * getdT() * pidProfile->I8[axis], -250.0f, 250.0f); // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. // I coefficient (I8) moved before integration to make limiting independent from PID settings @@ -257,8 +248,6 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // -----calculate total PID output axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000); - if (lowThrottlePidReduction) axisPID[axis] /= 3; - #ifdef GTUNE if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { calculate_Gtune(axis); @@ -333,7 +322,7 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate gyroRate = gyroADC[axis] / 4; RateError = AngleRateTmp - gyroRate; - uint16_t kP = (pidProfile->dynamic_pterm) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; + uint16_t kP = (pidProfile->dynamic_pid) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; // -----calculate P component if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { @@ -352,26 +341,14 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // Precision is critical, as I prevents from long-time drift. Thus, 32 bits integrator is used. // Time correction (to avoid different I scaling for different builds based on average cycle time) // is normalized to cycle time = 2048. - errorGyroI[axis] = errorGyroI[axis] + ((RateError * (uint16_t)targetPidLooptime) >> 11) * pidProfile->I8[axis]; + uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile) : pidProfile->I8[axis]; + + errorGyroI[axis] = errorGyroI[axis] + ((RateError * (uint16_t)targetPidLooptime) >> 11) * kI; // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. // I coefficient (I8) moved before integration to make limiting independent from PID settings errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13); - if ((pidProfile->rollPitchItermResetAlways || IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) && axis != YAW) { - if (ABS(gyroRate *10 / 41) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -pidProfile->itermResetOffset << 13, (int32_t) + pidProfile->itermResetOffset << 13); - } - - if (axis == YAW) { - if (ABS(gyroRate * 10 / 41) >= pidProfile->yawItermResetRate) errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) -YAW_ITERM_RESET_OFFSET << 13, (int32_t) + YAW_ITERM_RESET_OFFSET << 13); - } - - if (antiWindupProtection || motorLimitReached) { - errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]); - } else { - errorGyroILimit[axis] = ABS(errorGyroI[axis]); - } - ITerm = errorGyroI[axis] >> 13; //-----calculate D-term @@ -394,8 +371,6 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // -----calculate total PID output axisPID[axis] = PTerm + ITerm + DTerm; - if (lowThrottlePidReduction) axisPID[axis] /= 3; - #ifdef GTUNE if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { calculate_Gtune(axis); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 046adbcb66..30bffb98fe 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -22,7 +22,6 @@ #define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter #define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter -#define YAW_ITERM_RESET_OFFSET 15 // May be made configurable in the future, but not really needed for yaw #define DYNAMIC_PTERM_STICK_THRESHOLD 400 typedef enum { @@ -50,12 +49,6 @@ typedef enum { DELTA_FROM_MEASUREMENT } pidDeltaType_e; -typedef enum { - RESET_DISABLE = 0, - RESET_ITERM, - RESET_ITERM_AND_REDUCE_PID -} pidErrorResetOption_e; - typedef enum { SUPEREXPO_YAW_OFF = 0, SUPEREXPO_YAW_ON, @@ -71,15 +64,13 @@ typedef struct pidProfile_s { uint8_t I8[PID_ITEM_COUNT]; uint8_t D8[PID_ITEM_COUNT]; - uint8_t itermResetOffset; // Reset offset for Iterm uint16_t dterm_lpf_hz; // Delta Filter in hz uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy - uint16_t rollPitchItermResetRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates - uint8_t rollPitchItermResetAlways; // Reset Iterm also without SUPER EXPO - uint16_t yawItermResetRate; // Experimental threshold for resetting iterm for yaw on certain rates + uint16_t rollPitchItermIgnoreRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates + uint16_t yawItermIgnoreRate; // Experimental threshold for resetting iterm for yaw on certain rates uint16_t yaw_p_limit; uint8_t dterm_average_count; // Configurable delta count for dterm - uint8_t dynamic_pterm; + uint8_t dynamic_pid; // Dynamic PID implementation (currently only P and I) #ifdef GTUNE uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune @@ -98,10 +89,10 @@ typedef void (*pidControllerFuncPtr)(const pidProfile_t *pidProfile, const struc extern int16_t axisPID[XYZ_AXIS_COUNT]; extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; -bool antiWindupProtection; +bool airmodeWasActivated; extern uint32_t targetPidLooptime; void pidSetController(pidControllerType_e type); -void pidResetErrorGyroState(uint8_t resetOption); +void pidResetErrorGyroState(void); void setTargetPidLooptime(uint8_t pidProcessDenom); diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 3264b0269a..fdde2cf1a8 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -124,15 +124,6 @@ throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband return THROTTLE_HIGH; } -rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig) -{ - if (((rcData[PITCH] < (rxConfig->midrc + AIRMODEDEADBAND)) && (rcData[PITCH] > (rxConfig->midrc -AIRMODEDEADBAND))) - && ((rcData[ROLL] < (rxConfig->midrc + AIRMODEDEADBAND)) && (rcData[ROLL] > (rxConfig->midrc -AIRMODEDEADBAND)))) - return CENTERED; - - return NOT_CENTERED; -} - void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch) { static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h index 7756aed071..eaec277ae0 100644 --- a/src/main/io/rc_controls.h +++ b/src/main/io/rc_controls.h @@ -252,4 +252,3 @@ bool isUsingSticksForArming(void); int32_t getRcStickDeflection(int32_t axis, uint16_t midrc); bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationConditions, boxId_e modeId); -rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 1ea06c9f0a..6ecc665b1e 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -698,6 +698,7 @@ const clivalue_t valueTable[] = { { "super_expo_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactor, .config.minmax = {1, 100 } }, { "super_expo_factor_yaw", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactorYaw, .config.minmax = {1, 100 } }, { "super_expo_yaw", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.superExpoYawMode, .config.lookup = { TABLE_SUPEREXPO_YAW } }, + { "airmode_activate_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.airModeActivateThreshold, .config.minmax = {1000, 2000 } }, { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } }, { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } }, @@ -730,11 +731,9 @@ const clivalue_t valueTable[] = { { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } }, { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } }, { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } }, - { "dynamic_pterm", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dynamic_pterm, .config.lookup = { TABLE_OFF_ON } }, - { "iterm_always_reset", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } }, - { "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } }, - { "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } }, - { "iterm_reset_offset", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermResetOffset, .config.minmax = { 0, 100 } }, + { "dynamic_pid", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dynamic_pid, .config.lookup = { TABLE_OFF_ON } }, + { "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {50, 1000 } }, + { "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {25, 1000 } }, { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } }, diff --git a/src/main/mw.c b/src/main/mw.c index b9da3e6b70..125674c9e7 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -101,6 +101,8 @@ enum { #define GYRO_WATCHDOG_DELAY 80 // delay for gyro sync +#define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine + uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop int16_t magHold; @@ -113,7 +115,6 @@ static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the m extern uint32_t currentTime; extern uint8_t PIDweight[3]; -extern bool antiWindupProtection; uint16_t filteredCycleTime; static bool isRXDataNew; @@ -453,6 +454,7 @@ void updateMagHold(void) void processRx(void) { static bool armedBeeperOn = false; + static bool airmodeIsActivated; calculateRxChannelsAndUpdateFailsafe(currentTime); @@ -474,27 +476,17 @@ void processRx(void) } throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); - rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(&masterConfig.rxConfig); + + if (IS_RC_MODE_ACTIVE(BOXAIRMODE) && ARMING_FLAG(ARMED)) { + if (rcCommand[THROTTLE] >= masterConfig.rxConfig.airModeActivateThreshold) airmodeIsActivated = true; // Prevent Iterm from being reset + } else { + airmodeIsActivated = false; + } /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air */ - if (throttleStatus == THROTTLE_LOW) { - if (IS_RC_MODE_ACTIVE(BOXAIRMODE) && !failsafeIsActive() && ARMING_FLAG(ARMED)) { - if (rollPitchStatus == CENTERED) { - antiWindupProtection = true; - } else { - antiWindupProtection = false; - } - } else { - if (IS_RC_MODE_ACTIVE(BOXAIRMODE)) { - pidResetErrorGyroState(RESET_ITERM); - } else { - pidResetErrorGyroState(RESET_ITERM_AND_REDUCE_PID); - } - } - } else { - pidResetErrorGyroState(RESET_DISABLE); - antiWindupProtection = false; + if (throttleStatus == THROTTLE_LOW && !airmodeIsActivated) { + pidResetErrorGyroState(); } // When armed and motors aren't spinning, do beeps and then disarm diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 6e2dd2124b..b6e1cfea30 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -124,9 +124,10 @@ typedef struct rxConfig_s { uint8_t rcSmoothing; uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands uint8_t max_aux_channel; - uint8_t superExpoFactor; // Super Expo Factor - uint8_t superExpoFactorYaw; // Super Expo Factor Yaw - uint8_t superExpoYawMode; // Seperate Super expo for yaw + uint8_t superExpoFactor; // Super Expo Factor + uint8_t superExpoFactorYaw; // Super Expo Factor Yaw + uint8_t superExpoYawMode; // Seperate Super expo for yaw + uint16_t airModeActivateThreshold; // Throttle setpoint where airmode gets activated uint16_t rx_min_usec; uint16_t rx_max_usec; diff --git a/src/main/version.h b/src/main/version.h index 009ff6e352..fd95e254dc 100644 --- a/src/main/version.h +++ b/src/main/version.h @@ -17,7 +17,7 @@ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) #define FC_VERSION_MINOR 7 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed +#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) From 404e250b73def5ddb0f5dc5044fc308685ec5973 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 08:31:00 +0200 Subject: [PATCH 51/85] Fix for iterm ignore accuracy --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 7e2a346238..dc17f886ed 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -104,7 +104,7 @@ uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile) { resetRate = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate; - uint32_t dynamicFactor = (1 << 8) - constrain(ABS(gyroADC[axis] << 8) / resetRate, 0, 1 << 8); + uint32_t dynamicFactor = (1 << 8) - constrain((ABS(gyroADC[axis]) << 6) / resetRate, 0, 1 << 8); dynamicKi = (pidProfile->I8[axis] * dynamicFactor) >> 8; From 6b3d26e21d7ae6caa10cbc02460a2cf80d5e8dd3 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 10:12:22 +0200 Subject: [PATCH 52/85] Slightly lower D default --- src/main/config/config.c | 4 ++-- src/main/version.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index b46ff756af..055c27a778 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -155,10 +155,10 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->P8[ROLL] = 45; pidProfile->I8[ROLL] = 55; - pidProfile->D8[ROLL] = 18; + pidProfile->D8[ROLL] = 15; pidProfile->P8[PITCH] = 45; pidProfile->I8[PITCH] = 55; - pidProfile->D8[PITCH] = 18; + pidProfile->D8[PITCH] = 15; pidProfile->P8[YAW] = 90; pidProfile->I8[YAW] = 50; pidProfile->D8[YAW] = 0; diff --git a/src/main/version.h b/src/main/version.h index fd95e254dc..3cd436cc25 100644 --- a/src/main/version.h +++ b/src/main/version.h @@ -16,8 +16,8 @@ */ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) -#define FC_VERSION_MINOR 7 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed +#define FC_VERSION_MINOR 8 // increment when a minor release is made (small new feature, change etc) +#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) From f8aefc9c6f3558cbf4ecb9ba7f74e73bf07f0172 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 10:46:23 +0200 Subject: [PATCH 53/85] Revert "Added 'ledstrip_visual_beeper' feature." This reverts commit d6e7ed3560ac2abe73d768c0558e4f367e7e3608. --- src/main/config/config.c | 1 - src/main/config/config_master.h | 1 - src/main/io/beeper.c | 8 -------- src/main/io/beeper.h | 1 - src/main/io/ledstrip.c | 24 +----------------------- src/main/io/serial_cli.c | 3 --- 6 files changed, 1 insertion(+), 37 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 055c27a778..53da557ec0 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -564,7 +564,6 @@ static void resetConf(void) #ifdef LED_STRIP applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT); applyDefaultLedStripConfig(masterConfig.ledConfigs); - masterConfig.ledstrip_visual_beeper = 0; #endif #ifdef SPRACINGF3 diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index c61df40e60..25a21afba7 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -119,7 +119,6 @@ typedef struct master_t { #ifdef LED_STRIP ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH]; hsvColor_t colors[CONFIGURABLE_COLOR_COUNT]; - uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on #endif #ifdef TRANSPONDER diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index b4893a1f16..e7ec349649 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -386,13 +386,6 @@ int beeperTableEntryCount(void) return (int)BEEPER_TABLE_ENTRY_COUNT; } -/* - * Returns true if the beeper is on, false otherwise - */ -bool isBeeperOn(void) { - return beeperIsOn; -} - #else // Stub out beeper functions if #BEEPER not defined @@ -404,6 +397,5 @@ uint32_t getArmingBeepTimeMicros(void) {return 0;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;} int beeperTableEntryCount(void) {return 0;} -bool isBeeperOn(void) {return false;} #endif diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 0f9f488ef6..7d3ef38ef5 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -53,4 +53,3 @@ uint32_t getArmingBeepTimeMicros(void); beeperMode_e beeperModeForTableIndex(int idx); const char *beeperNameForTableIndex(int idx); int beeperTableEntryCount(void); -bool isBeeperOn(void); diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index f0582a220d..a52ed8df09 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -34,41 +34,19 @@ #include "drivers/light_ws2811strip.h" #include "drivers/system.h" #include "drivers/serial.h" -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/gpio.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" #include -#include "common/axis.h" #include "io/rc_controls.h" #include "sensors/battery.h" -#include "sensors/sensors.h" -#include "sensors/boardalignment.h" -#include "sensors/gyro.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" #include "io/ledstrip.h" -#include "io/beeper.h" -#include "io/escservo.h" -#include "io/gimbal.h" -#include "io/serial.h" #include "flight/failsafe.h" -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" - -#include "telemetry/telemetry.h" #include "config/runtime_config.h" #include "config/config.h" -#include "config/config_profile.h" -#include "config/config_master.h" static bool ledStripInitialised = false; static bool ledStripEnabled = true; @@ -938,7 +916,7 @@ void updateLedStrip(void) return; } - if (IS_RC_MODE_ACTIVE(BOXLEDLOW) && !(masterConfig.ledstrip_visual_beeper && isBeeperOn())) { + if (IS_RC_MODE_ACTIVE(BOXLEDLOW)) { if (ledStripEnabled) { ledStripDisable(); ledStripEnabled = false; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 7f224e16a3..6ecc665b1e 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -770,9 +770,6 @@ const clivalue_t valueTable[] = { { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } }, { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } }, { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } }, -#ifdef LED_STRIP - { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } }, -#endif }; #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) From df6d564a9dd2dc4fa5b8d7cab76b5b27cff8db8a Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 14:05:52 +0200 Subject: [PATCH 54/85] Revert "Revert "Added 'ledstrip_visual_beeper' feature."" This reverts commit f8aefc9c6f3558cbf4ecb9ba7f74e73bf07f0172. --- src/main/config/config.c | 1 + src/main/config/config_master.h | 1 + src/main/io/beeper.c | 8 ++++++++ src/main/io/beeper.h | 1 + src/main/io/ledstrip.c | 24 +++++++++++++++++++++++- src/main/io/serial_cli.c | 3 +++ 6 files changed, 37 insertions(+), 1 deletion(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 53da557ec0..055c27a778 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -564,6 +564,7 @@ static void resetConf(void) #ifdef LED_STRIP applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT); applyDefaultLedStripConfig(masterConfig.ledConfigs); + masterConfig.ledstrip_visual_beeper = 0; #endif #ifdef SPRACINGF3 diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 25a21afba7..c61df40e60 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -119,6 +119,7 @@ typedef struct master_t { #ifdef LED_STRIP ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH]; hsvColor_t colors[CONFIGURABLE_COLOR_COUNT]; + uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on #endif #ifdef TRANSPONDER diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index e7ec349649..b4893a1f16 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -386,6 +386,13 @@ int beeperTableEntryCount(void) return (int)BEEPER_TABLE_ENTRY_COUNT; } +/* + * Returns true if the beeper is on, false otherwise + */ +bool isBeeperOn(void) { + return beeperIsOn; +} + #else // Stub out beeper functions if #BEEPER not defined @@ -397,5 +404,6 @@ uint32_t getArmingBeepTimeMicros(void) {return 0;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;} int beeperTableEntryCount(void) {return 0;} +bool isBeeperOn(void) {return false;} #endif diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 7d3ef38ef5..0f9f488ef6 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -53,3 +53,4 @@ uint32_t getArmingBeepTimeMicros(void); beeperMode_e beeperModeForTableIndex(int idx); const char *beeperNameForTableIndex(int idx); int beeperTableEntryCount(void); +bool isBeeperOn(void); diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index a52ed8df09..f0582a220d 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -34,19 +34,41 @@ #include "drivers/light_ws2811strip.h" #include "drivers/system.h" #include "drivers/serial.h" +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/gpio.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" #include +#include "common/axis.h" #include "io/rc_controls.h" #include "sensors/battery.h" +#include "sensors/sensors.h" +#include "sensors/boardalignment.h" +#include "sensors/gyro.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" #include "io/ledstrip.h" +#include "io/beeper.h" +#include "io/escservo.h" +#include "io/gimbal.h" +#include "io/serial.h" #include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" + +#include "telemetry/telemetry.h" #include "config/runtime_config.h" #include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" static bool ledStripInitialised = false; static bool ledStripEnabled = true; @@ -916,7 +938,7 @@ void updateLedStrip(void) return; } - if (IS_RC_MODE_ACTIVE(BOXLEDLOW)) { + if (IS_RC_MODE_ACTIVE(BOXLEDLOW) && !(masterConfig.ledstrip_visual_beeper && isBeeperOn())) { if (ledStripEnabled) { ledStripDisable(); ledStripEnabled = false; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 6ecc665b1e..7f224e16a3 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -770,6 +770,9 @@ const clivalue_t valueTable[] = { { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } }, { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } }, { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } }, +#ifdef LED_STRIP + { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } }, +#endif }; #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) From aa61bd4fb4e5219dfacae91c3b9ad20d6c4051d4 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 21:47:57 +0200 Subject: [PATCH 55/85] Replace yaw_jump_prevention_limit by D gain for yaw // new defaults based on flight tests --- src/main/config/config.c | 17 ++++++++--------- src/main/flight/mixer.c | 5 ----- src/main/flight/mixer.h | 4 ---- src/main/flight/pid.c | 31 ++++++++++++++++++++++++------- src/main/flight/pid.h | 2 ++ src/main/io/serial_cli.c | 1 - 6 files changed, 34 insertions(+), 26 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 055c27a778..9936b78a13 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -140,7 +140,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 136; +static const uint8_t EEPROM_CONF_VERSION = 137; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -154,14 +154,14 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->pidController = 1; pidProfile->P8[ROLL] = 45; - pidProfile->I8[ROLL] = 55; + pidProfile->I8[ROLL] = 40; pidProfile->D8[ROLL] = 15; pidProfile->P8[PITCH] = 45; - pidProfile->I8[PITCH] = 55; + pidProfile->I8[PITCH] = 40; pidProfile->D8[PITCH] = 15; pidProfile->P8[YAW] = 90; - pidProfile->I8[YAW] = 50; - pidProfile->D8[YAW] = 0; + pidProfile->I8[YAW] = 45; + pidProfile->D8[YAW] = 10; pidProfile->P8[PIDALT] = 50; pidProfile->I8[PIDALT] = 0; pidProfile->D8[PIDALT] = 0; @@ -184,8 +184,8 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_lpf_hz = 80; - pidProfile->rollPitchItermIgnoreRate = 200; - pidProfile->yawItermIgnoreRate = 50;; + pidProfile->rollPitchItermIgnoreRate = 180; + pidProfile->yawItermIgnoreRate = 35; pidProfile->dterm_lpf_hz = 110; // filtering ON by default pidProfile->dynamic_pid = 1; @@ -308,7 +308,7 @@ void resetSerialConfig(serialConfig_t *serialConfig) static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcRate8 = 100; - controlRateConfig->rcExpo8 = 60; + controlRateConfig->rcExpo8 = 70; controlRateConfig->thrMid8 = 50; controlRateConfig->thrExpo8 = 0; controlRateConfig->dynThrPID = 20; @@ -330,7 +330,6 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) { void resetMixerConfig(mixerConfig_t *mixerConfig) { mixerConfig->yaw_motor_direction = 1; - mixerConfig->yaw_jump_prevention_limit = 200; #ifdef USE_SERVOS mixerConfig->tri_unarmed_servo = 1; mixerConfig->servo_lowpass_freq = 400; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index c777ca39f7..87ee5f1871 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -761,11 +761,6 @@ void mixTable(void) bool isFailsafeActive = failsafeIsActive(); // TODO - Find out if failsafe checks are really needed here in mixer code - if (motorCount >= 4 && mixerConfig->yaw_jump_prevention_limit < YAW_JUMP_PREVENTION_LIMIT_HIGH) { - // prevent "yaw jump" during yaw correction - axisPID[YAW] = constrain(axisPID[YAW], -mixerConfig->yaw_jump_prevention_limit - ABS(rcCommand[YAW]), mixerConfig->yaw_jump_prevention_limit + ABS(rcCommand[YAW])); - } - // Initial mixer concept by bdoiron74 reused and optimized for Air Mode int16_t rollPitchYawMix[MAX_SUPPORTED_MOTORS]; int16_t rollPitchYawMixMax = 0; // assumption: symetrical about zero. diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index a1f79d5a8f..109102f20c 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -19,9 +19,6 @@ #define MAX_SUPPORTED_MOTORS 12 #define MAX_SUPPORTED_SERVOS 8 -#define YAW_JUMP_PREVENTION_LIMIT_LOW 80 -#define YAW_JUMP_PREVENTION_LIMIT_HIGH 500 - // Note: this is called MultiType/MULTITYPE_* in baseflight. typedef enum mixerMode @@ -71,7 +68,6 @@ typedef struct mixer_s { typedef struct mixerConfig_s { int8_t yaw_motor_direction; - uint16_t yaw_jump_prevention_limit; // make limit configurable (original fixed value was 100) #ifdef USE_SERVOS uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed uint16_t servo_lowpass_freq; // lowpass servo filter frequency selection; 1/1000ths of loop freq diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index dc17f886ed..96cf037ca9 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -231,7 +231,15 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ //-----calculate D-term if (axis == YAW) { if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); - DTerm = 0; + + axisPID[axis] = lrintf(PTerm + ITerm); + + if (motorCount >= 4) { + int16_t yaw_jump_prevention_limit = constrain(YAW_JUMP_PREVENTION_LIMIT_HIGH - (pidProfile->D8[axis] << 3), YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH); + + // prevent "yaw jump" during yaw correction + axisPID[YAW] = constrain(axisPID[YAW], -yaw_jump_prevention_limit - ABS(rcCommand[YAW]), yaw_jump_prevention_limit + ABS(rcCommand[YAW])); + } } else { delta = -(gyroRate - lastRate[axis]); lastRate[axis] = gyroRate; @@ -243,10 +251,10 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1(delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT()); DTerm = constrainf(luxDTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f); - } - // -----calculate total PID output - axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000); + // -----calculate total PID output + axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000); + } #ifdef GTUNE if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { @@ -354,7 +362,15 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate //-----calculate D-term if (axis == YAW) { if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); - DTerm = 0; + + axisPID[axis] = PTerm + ITerm; + + if (motorCount >= 4) { + int16_t yaw_jump_prevention_limit = constrain(YAW_JUMP_PREVENTION_LIMIT_HIGH - (pidProfile->D8[axis] << 3), YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH); + + // prevent "yaw jump" during yaw correction + axisPID[YAW] = constrain(axisPID[YAW], -yaw_jump_prevention_limit - ABS(rcCommand[YAW]), yaw_jump_prevention_limit + ABS(rcCommand[YAW])); + } } else { delta = -(gyroRate - lastRate[axis]); lastRate[axis] = gyroRate; @@ -366,10 +382,11 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT()); DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8; + + // -----calculate total PID output + axisPID[axis] = PTerm + ITerm + DTerm; } - // -----calculate total PID output - axisPID[axis] = PTerm + ITerm + DTerm; #ifdef GTUNE if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 30bffb98fe..1103f7bd9a 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -21,6 +21,8 @@ #define GYRO_I_MAX 256 // Gyro I limiter #define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter #define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter +#define YAW_JUMP_PREVENTION_LIMIT_LOW 80 +#define YAW_JUMP_PREVENTION_LIMIT_HIGH 400 #define DYNAMIC_PTERM_STICK_THRESHOLD 400 diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 7f224e16a3..12fa08adf3 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -677,7 +677,6 @@ const clivalue_t valueTable[] = { { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } }, { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } }, - { "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, .config.minmax = { YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH } }, { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } }, #ifdef USE_SERVOS { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } }, From 80e047e6518c69894dccc04f7153f5f9b73375a8 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 21:59:34 +0200 Subject: [PATCH 56/85] Fix compile errors in ledstrip.c --- src/main/io/ledstrip.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index f0582a220d..cf85b7db37 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -57,11 +57,13 @@ #include "io/escservo.h" #include "io/gimbal.h" #include "io/serial.h" +#include "io/gps.h" #include "flight/failsafe.h" #include "flight/mixer.h" #include "flight/pid.h" #include "flight/imu.h" +#include "flight/navigation.h" #include "telemetry/telemetry.h" From f1d422c322ec168291f152d9ee1f41256104dd02 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 23:10:09 +0200 Subject: [PATCH 57/85] Seperate ONESHOT125 feature from fast_pwm_protocol --- src/main/config/config.c | 2 +- src/main/config/config_master.h | 2 +- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/pwm_mapping.h | 2 +- src/main/drivers/pwm_output.h | 7 ++++--- src/main/io/serial_cli.c | 2 +- src/main/io/serial_msp.c | 3 --- src/main/main.c | 11 +++++++++-- 8 files changed, 18 insertions(+), 13 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 9936b78a13..6ffab2de54 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -486,7 +486,7 @@ static void resetConf(void) masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; #endif masterConfig.servo_pwm_rate = 50; - masterConfig.fast_pwm_protocol = 0; + masterConfig.fast_pwm_protocol = 1; masterConfig.use_unsyncedPwm = 0; #ifdef CC3D masterConfig.use_buzzer_p6 = 0; diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index c61df40e60..c0695be6ac 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -34,7 +34,7 @@ typedef struct master_t { uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) - uint8_t fast_pwm_protocol; // Fast Pwm Protocol + uint8_t fast_pwm_protocol; // Pwm Protocol uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop #ifdef USE_SERVOS diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 0ce82b5184..b95efed1da 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -929,7 +929,7 @@ if (init->useBuzzerP6) { } #endif if (init->useFastPwm) { - pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->fastPwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse); + pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse); pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; } else if (isMotorBrushed(init->motorPwmRate)) { pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 1edf1458d3..aaaf4ac6b2 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -71,7 +71,7 @@ typedef struct drv_pwm_config_s { #ifdef USE_SERVOS bool useServos; bool useChannelForwarding; // configure additional channels as servos - uint8_t fastPwmProtocolType; + uint8_t pwmProtocolType; uint16_t servoPwmRate; uint16_t servoCenterPulse; #endif diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 615ffa7ac2..060d7f3884 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -18,9 +18,10 @@ #pragma once typedef enum { - PWM_TYPE_ONESHOT125 = 0, - PWM_TYPE_ONESHOT42 = 1, - PWM_TYPE_MULTISHOT = 2 + PWM_TYPE_CONVENTIONAL = 0, + PWM_TYPE_ONESHOT125, + PWM_TYPE_ONESHOT42, + PWM_TYPE_MULTISHOT } FastPwmProtocolTypes_e; void pwmWriteMotor(uint8_t index, uint16_t value); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 12fa08adf3..911cc9ecc4 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -443,7 +443,7 @@ static const char * const lookupTableSuperExpoYaw[] = { }; static const char * const lookupTableFastPwm[] = { - "ONESHOT125", "ONESHOT42", "MULTISHOT" + "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT" }; typedef struct lookupTableEntry_s { diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index aa0d23b8c5..f243b30016 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -171,9 +171,6 @@ void setGyroSamplingSpeed(uint16_t looptime) { masterConfig.pid_process_denom = 1; } #endif - - // Oneshot125 protection - if ((masterConfig.fast_pwm_protocol == 0) && ((masterConfig.gyro_sync_denom * gyroSampleRate) == 125) && masterConfig.pid_process_denom < 3) masterConfig.pid_process_denom = 3; } } diff --git a/src/main/main.c b/src/main/main.c index 06a7e99c3f..6f301131e8 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -44,6 +44,7 @@ #include "drivers/compass.h" #include "drivers/pwm_mapping.h" #include "drivers/pwm_rx.h" +#include "drivers/pwm_output.h" #include "drivers/adc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_bst.h" @@ -311,8 +312,14 @@ void init(void) pwm_params.servoPwmRate = masterConfig.servo_pwm_rate; #endif - pwm_params.useFastPwm = feature(FEATURE_ONESHOT125); // Configurator feature abused for enabling Fast PWM - pwm_params.fastPwmProtocolType = masterConfig.fast_pwm_protocol; + if (masterConfig.fast_pwm_protocol == PWM_TYPE_ONESHOT125) { + featureSet(FEATURE_ONESHOT125); + } else { + featureClear(FEATURE_ONESHOT125); + } + + pwm_params.useFastPwm = (masterConfig.fast_pwm_protocol != PWM_TYPE_CONVENTIONAL) ? true : false; // Configurator feature abused for enabling Fast PWM + pwm_params.pwmProtocolType = masterConfig.fast_pwm_protocol; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm; From c8945c179af94c7abf62cc7b4b8ca61ba907d5fb Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 24 May 2016 23:46:32 +0200 Subject: [PATCH 58/85] Fix ALIENWII Target --- src/main/config/config.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 6ffab2de54..8e259c5cb3 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -628,7 +628,6 @@ static void resetConf(void) currentProfile->pidProfile.pidController = 2; masterConfig.failsafeConfig.failsafe_delay = 2; masterConfig.failsafeConfig.failsafe_off_delay = 0; - masterConfig.mixerConfig.yaw_jump_prevention_limit = 500; currentControlRateProfile->rcRate8 = 100; currentControlRateProfile->rates[FD_PITCH] = 20; currentControlRateProfile->rates[FD_ROLL] = 20; From 94d9df4cc1f613400fb2b8dec84954826ffd255a Mon Sep 17 00:00:00 2001 From: mikeller Date: Wed, 25 May 2016 23:52:40 +1200 Subject: [PATCH 59/85] Fixed failure to disable beeping on FC init. Also, fixed spelling. --- src/main/config/config.c | 8 ++++---- src/main/config/config.h | 4 ++-- src/main/config/config_master.h | 2 +- src/main/io/beeper.c | 2 +- src/main/io/serial_cli.c | 4 ++-- src/main/main.c | 2 +- 6 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 8e259c5cb3..e718bcea03 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -1115,12 +1115,12 @@ void setBeeperOffMask(uint32_t mask) masterConfig.beeper_off_flags = mask; } -uint32_t getPreferedBeeperOffMask(void) +uint32_t getPreferredBeeperOffMask(void) { - return masterConfig.prefered_beeper_off_flags; + return masterConfig.preferred_beeper_off_flags; } -void setPreferedBeeperOffMask(uint32_t mask) +void setPreferredBeeperOffMask(uint32_t mask) { - masterConfig.prefered_beeper_off_flags = mask; + masterConfig.preferred_beeper_off_flags = mask; } diff --git a/src/main/config/config.h b/src/main/config/config.h index 7cb16dc900..55ae18185a 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -60,8 +60,8 @@ void beeperOffClear(uint32_t mask); void beeperOffClearAll(void); uint32_t getBeeperOffMask(void); void setBeeperOffMask(uint32_t mask); -uint32_t getPreferedBeeperOffMask(void); -void setPreferedBeeperOffMask(uint32_t mask); +uint32_t getPreferredBeeperOffMask(void); +void setPreferredBeeperOffMask(uint32_t mask); void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index c0695be6ac..ecc4af7ec8 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -139,7 +139,7 @@ typedef struct master_t { #endif uint32_t beeper_off_flags; - uint32_t prefered_beeper_off_flags; + uint32_t preferred_beeper_off_flags; uint8_t magic_ef; // magic number, should be 0xEF uint8_t chk; // XOR checksum diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index b4893a1f16..1448a6b5e1 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -172,7 +172,7 @@ typedef struct beeperTableEntry_s { { BEEPER_ENTRY(BEEPER_USB, 17, NULL, "ON_USB") }, { BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") }, - { BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERED") }, + { BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERRED") }, }; static const beeperTableEntry_t *currentBeeperEntry = NULL; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 911cc9ecc4..56d143a0d3 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -2177,7 +2177,7 @@ static void cliBeeper(char *cmdline) beeperOffSetAll(beeperCount-2); else if (i == BEEPER_PREFERENCE-1) - setBeeperOffMask(getPreferedBeeperOffMask()); + setBeeperOffMask(getPreferredBeeperOffMask()); else { mask = 1 << i; beeperOffSet(mask); @@ -2189,7 +2189,7 @@ static void cliBeeper(char *cmdline) beeperOffClearAll(); else if (i == BEEPER_PREFERENCE-1) - setPreferedBeeperOffMask(getBeeperOffMask()); + setPreferredBeeperOffMask(getBeeperOffMask()); else { mask = 1 << i; beeperOffClear(mask); diff --git a/src/main/main.c b/src/main/main.c index 6f301131e8..0172dc2ebd 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -480,7 +480,7 @@ void init(void) LED1_TOGGLE; LED0_TOGGLE; delay(25); - if (!(getPreferedBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) BEEP_ON; + if (!(getBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) BEEP_ON; delay(25); BEEP_OFF; } From 935ad7f61351aba47de95bb6f4472cbd4ac2fb7d Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 25 May 2016 22:43:06 +0200 Subject: [PATCH 60/85] Fix Luxfloat iterm issue // New Ignore Iterm default --- src/main/config/config.c | 4 ++-- src/main/flight/pid.c | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index e718bcea03..081084c07b 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -161,7 +161,7 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->D8[PITCH] = 15; pidProfile->P8[YAW] = 90; pidProfile->I8[YAW] = 45; - pidProfile->D8[YAW] = 10; + pidProfile->D8[YAW] = 20; pidProfile->P8[PIDALT] = 50; pidProfile->I8[PIDALT] = 0; pidProfile->D8[PIDALT] = 0; @@ -184,7 +184,7 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_lpf_hz = 80; - pidProfile->rollPitchItermIgnoreRate = 180; + pidProfile->rollPitchItermIgnoreRate = 900; pidProfile->yawItermIgnoreRate = 35; pidProfile->dterm_lpf_hz = 110; // filtering ON by default pidProfile->dynamic_pid = 1; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 96cf037ca9..5983e7a298 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -222,7 +222,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // -----calculate I component. uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile) : pidProfile->I8[axis]; - errorGyroIf[axis] = constrainf(kI + luxITermScale * RateError * getdT() * pidProfile->I8[axis], -250.0f, 250.0f); + errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * kI, -250.0f, 250.0f); // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. // I coefficient (I8) moved before integration to make limiting independent from PID settings From fb7cfffdebb403ae244350552eeb52e14b15d724 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 25 May 2016 23:51:10 +0200 Subject: [PATCH 61/85] Anti Desync feature for ESC's // Experimental --- src/main/config/config.c | 3 ++- src/main/flight/mixer.c | 9 +++++++++ src/main/io/escservo.h | 1 + src/main/io/serial_cli.c | 1 + 4 files changed, 13 insertions(+), 1 deletion(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 081084c07b..4ac6984a67 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -140,7 +140,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 137; +static const uint8_t EEPROM_CONF_VERSION = 138; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -236,6 +236,7 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig) escAndServoConfig->maxthrottle = 1850; escAndServoConfig->mincommand = 1000; escAndServoConfig->servoCenterPulse = 1500; + escAndServoConfig->escDesyncProtection = 0; } void resetFlight3DConfig(flight3DConfig_t *flight3DConfig) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 87ee5f1871..f305ded593 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -854,6 +854,15 @@ void mixTable(void) motor[i] = escAndServoConfig->mincommand; } } + + // Experimental Code. Anti Desync feature for ESC's + if (escAndServoConfig->escDesyncProtection) { + const int16_t maxThrottleStep = escAndServoConfig->escDesyncProtection / (1000 / targetPidLooptime); + static int16_t motorPrevious[MAX_SUPPORTED_MOTORS]; + + motor[i] = constrain(motor[i], motorPrevious[i] - maxThrottleStep, motorPrevious[i] + maxThrottleStep); + motorPrevious[i] = motor[i]; + } } // Disarmed mode diff --git a/src/main/io/escservo.h b/src/main/io/escservo.h index 66cd7db59e..b73f9920f3 100644 --- a/src/main/io/escservo.h +++ b/src/main/io/escservo.h @@ -24,4 +24,5 @@ typedef struct escAndServoConfig_s { uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500. + uint16_t escDesyncProtection; // Value that a motor is allowed to increase or decrease in a period of 1ms } escAndServoConfig_t; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 56d143a0d3..a400d7509e 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -565,6 +565,7 @@ const clivalue_t valueTable[] = { { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, + { "anti_desync_power_step", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.escDesyncProtection, .config.minmax = { 0, 2000 } }, { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently From 754982f48090c1510f49c2e7560b8ccb5d896fba Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 30 May 2016 13:02:41 +0200 Subject: [PATCH 62/85] Add higher power function to Super Expo --- q | 59 +++++++++++++++++++++++++++++++++++++++++++ src/main/flight/pid.c | 4 ++- 2 files changed, 62 insertions(+), 1 deletion(-) create mode 100644 q diff --git a/q b/q new file mode 100644 index 0000000000..04586033b6 --- /dev/null +++ b/q @@ -0,0 +1,59 @@ +diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c +index fdde2cf..53464ef 100644 +--- a/src/main/io/rc_controls.c ++++ b/src/main/io/rc_controls.c +@@ -67,6 +67,7 @@ static pidProfile_t *pidProfile; + static bool isUsingSticksToArm = true; +  + int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW ++int16_t rcCommandSmooth[4]; // Smoothed RcCommand +  + uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e +  +diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h +index eaec277..dd8afaf 100644 +--- a/src/main/io/rc_controls.h ++++ b/src/main/io/rc_controls.h +@@ -147,6 +147,7 @@ typedef struct controlRateConfig_s { + } controlRateConfig_t; +  + extern int16_t rcCommand[4]; ++extern int16_t rcCommandSmooth[4]; // Smoothed RcCommand +  + typedef struct rcControlsConfig_s { + uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. +diff --git a/src/main/mw.c b/src/main/mw.c +index 125674c..5da79cf 100644 +--- a/src/main/mw.c ++++ b/src/main/mw.c +@@ -181,7 +181,7 @@ void filterRc(void) +  + if (isRXDataNew) { + for (int channel=0; channel < 4; channel++) { +- deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); ++ deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); + lastCommand[channel] = rcCommand[channel]; + } +  +@@ -194,7 +194,7 @@ void filterRc(void) + // Interpolate steps of rcCommand + if (factor > 0) { + for (int channel=0; channel < 4; channel++) { +- rcCommand[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; ++ rcCommandSmooth[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; + } + } else { + factor = 0; +@@ -649,8 +649,11 @@ void subTaskMainSubprocesses(void) { +  + const uint32_t startTime = micros(); +  ++ filterRc(); ++ + if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) { +- filterRc(); ++ int axis; ++ for (axis = 0; axis <= 4; axis++) rcCommand[axis] = rcCommandSmooth[axis]; + } +  + // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 5983e7a298..11fb52abb5 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -81,8 +81,10 @@ float calculateExpoPlus(int axis, const rxConfig_t *rxConfig) { if (axis == YAW && !rxConfig->superExpoYawMode) { propFactor = 1.0f; } else { + float rcFactor = (ABS(rcCommand[axis]) / 500.0f); + superExpoFactor = (axis == YAW) ? rxConfig->superExpoFactorYaw : rxConfig->superExpoFactor; - propFactor = constrainf(1.0f - ((superExpoFactor / 100.0f) * (ABS(rcCommand[axis]) / 500.0f)), 0.0f, 1.0f); + propFactor = constrainf(1.0f - ((superExpoFactor / 100.0f) * rcFactor * rcFactor * rcFactor), 0.0f, 1.0f); } return propFactor; From 23b0e79eff2f71ac20f972727da7f467f7a3346f Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 30 May 2016 19:47:53 +0200 Subject: [PATCH 63/85] Smoother Iterm Ignore transition --- src/main/config/config.c | 4 ++-- src/main/flight/pid.c | 3 +-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 4ac6984a67..910954cdc6 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -184,8 +184,8 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_lpf_hz = 80; - pidProfile->rollPitchItermIgnoreRate = 900; - pidProfile->yawItermIgnoreRate = 35; + pidProfile->rollPitchItermIgnoreRate = 200; + pidProfile->yawItermIgnoreRate = 45; pidProfile->dterm_lpf_hz = 110; // filtering ON by default pidProfile->dynamic_pid = 1; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 11fb52abb5..3e741c0c0e 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -106,8 +106,7 @@ uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile) { resetRate = (axis == YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate; - uint32_t dynamicFactor = (1 << 8) - constrain((ABS(gyroADC[axis]) << 6) / resetRate, 0, 1 << 8); - + uint32_t dynamicFactor = ((resetRate << 16) / (resetRate + ABS(gyroADC[axis]))) >> 8; dynamicKi = (pidProfile->I8[axis] * dynamicFactor) >> 8; return dynamicKi; From 3470181a0fc844db8955ec53d9ac4881dabfa6df Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Mon, 30 May 2016 20:34:33 +0200 Subject: [PATCH 64/85] Add feature for SuperExpo and Airmode // Super Expo by default activated --- src/main/config/config.c | 6 +++--- src/main/config/config.h | 2 ++ src/main/flight/pid.c | 4 ++-- src/main/io/rc_controls.c | 7 +++++++ src/main/io/rc_controls.h | 2 ++ src/main/io/serial_cli.c | 3 ++- src/main/io/serial_msp.c | 4 ++-- src/main/mw.c | 10 +++++----- 8 files changed, 25 insertions(+), 13 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 910954cdc6..f7d1cb57a5 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -398,7 +398,7 @@ static void resetConf(void) #endif featureSet(FEATURE_FAILSAFE); - featureSet(FEATURE_ONESHOT125); + featureSet(FEATURE_SUPEREXPO); // global settings masterConfig.current_profile_index = 0; // default profile @@ -461,8 +461,8 @@ static void resetConf(void) masterConfig.rxConfig.max_aux_channel = 6; masterConfig.rxConfig.superExpoFactor = 30; masterConfig.rxConfig.airModeActivateThreshold = 1350; - masterConfig.rxConfig.superExpoFactorYaw = 30; - masterConfig.rxConfig.superExpoYawMode = 0; + masterConfig.rxConfig.superExpoFactorYaw = 40; + masterConfig.rxConfig.superExpoYawMode = 1; resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges); diff --git a/src/main/config/config.h b/src/main/config/config.h index 55ae18185a..24fe20ea62 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -44,6 +44,8 @@ typedef enum { FEATURE_BLACKBOX = 1 << 19, FEATURE_CHANNEL_FORWARDING = 1 << 20, FEATURE_TRANSPONDER = 1 << 21, + FEATURE_AIRMODE = 1 << 22, + FEATURE_SUPEREXPO = 1 << 23, } features_e; void handleOneshotFeatureChangeOnRestart(void); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 3e741c0c0e..783c627ec2 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -209,7 +209,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ uint16_t kP = (pidProfile->dynamic_pid) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; // -----calculate P component - if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { + if ((isSuperExpoActive() && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { PTerm = (luxPTermScale * kP * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig)); } else { PTerm = luxPTermScale * RateError * kP * tpaFactor; @@ -334,7 +334,7 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate uint16_t kP = (pidProfile->dynamic_pid) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; // -----calculate P component - if ((IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { + if ((isSuperExpoActive() && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { PTerm = (kP * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig))) >> 7; } else { PTerm = (RateError * kP * PIDweight[axis] / 100) >> 7; diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index fdde2cf1a8..a72efd990e 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -70,6 +70,13 @@ int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+ uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e +bool isAirmodeActive(void) { + return (IS_RC_MODE_ACTIVE(BOXAIRMODE) || feature(FEATURE_AIRMODE)); +} + +bool isSuperExpoActive(void) { + return (IS_RC_MODE_ACTIVE(BOXSUPEREXPO) || feature(FEATURE_SUPEREXPO)); +} void blackboxLogInflightAdjustmentEvent(adjustmentFunction_e adjustmentFunction, int32_t newValue) { #ifndef BLACKBOX diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h index eaec277ae0..8cbb078a4d 100644 --- a/src/main/io/rc_controls.h +++ b/src/main/io/rc_controls.h @@ -243,6 +243,8 @@ typedef struct adjustmentState_s { #define MAX_ADJUSTMENT_RANGE_COUNT 15 +bool isAirmodeActive(void); +bool isSuperExpoActive(void); void resetAdjustmentStates(void); void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig); void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index a400d7509e..ea6801e079 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -194,7 +194,8 @@ static const char * const featureNames[] = { "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", - "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", NULL + "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO", + NULL }; // sync this with rxFailsafeChannelMode_e diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index f243b30016..a65b224b86 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -542,8 +542,8 @@ void mspInit(serialConfig_t *serialConfig) activeBoxIds[activeBoxIdCount++] = BOXHORIZON; } - activeBoxIds[activeBoxIdCount++] = BOXAIRMODE; - activeBoxIds[activeBoxIdCount++] = BOXSUPEREXPO; + if (!feature(FEATURE_AIRMODE)) activeBoxIds[activeBoxIdCount++] = BOXAIRMODE; + if (!feature(FEATURE_SUPEREXPO)) activeBoxIds[activeBoxIdCount++] = BOXSUPEREXPO; activeBoxIds[activeBoxIdCount++] = BOX3DDISABLESWITCH; if (sensors(SENSOR_BARO)) { diff --git a/src/main/mw.c b/src/main/mw.c index 125674c9e7..54401519b6 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -454,7 +454,7 @@ void updateMagHold(void) void processRx(void) { static bool armedBeeperOn = false; - static bool airmodeIsActivated; + static bool wasAirmodeIsActivated; calculateRxChannelsAndUpdateFailsafe(currentTime); @@ -477,15 +477,15 @@ void processRx(void) throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle); - if (IS_RC_MODE_ACTIVE(BOXAIRMODE) && ARMING_FLAG(ARMED)) { - if (rcCommand[THROTTLE] >= masterConfig.rxConfig.airModeActivateThreshold) airmodeIsActivated = true; // Prevent Iterm from being reset + if (isAirmodeActive() && ARMING_FLAG(ARMED)) { + if (rcCommand[THROTTLE] >= masterConfig.rxConfig.airModeActivateThreshold) wasAirmodeIsActivated = true; // Prevent Iterm from being reset } else { - airmodeIsActivated = false; + wasAirmodeIsActivated = false; } /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air */ - if (throttleStatus == THROTTLE_LOW && !airmodeIsActivated) { + if (throttleStatus == THROTTLE_LOW && !wasAirmodeIsActivated) { pidResetErrorGyroState(); } From 2df7e3cefae52ef7018bb93f2a824247bd574a38 Mon Sep 17 00:00:00 2001 From: sblakemore Date: Wed, 2 Dec 2015 08:56:28 +1000 Subject: [PATCH 65/85] Add RTC6705 SPI VTX support --- src/main/blackbox/blackbox.c | 1 + src/main/blackbox/blackbox_io.c | 1 + src/main/config/config.c | 8 ++ src/main/config/config_master.h | 9 ++ src/main/drivers/vtx_rtc6705.c | 191 ++++++++++++++++++++++++++++++++ src/main/drivers/vtx_rtc6705.h | 38 +++++++ src/main/io/beeper.c | 1 + src/main/io/ledstrip.c | 1 + src/main/io/rc_controls.c | 16 +++ src/main/io/rc_controls.h | 1 + src/main/io/serial_cli.c | 82 ++++++++++++++ src/main/io/serial_msp.c | 1 + src/main/io/vtx.c | 146 ++++++++++++++++++++++++ src/main/io/vtx.h | 40 +++++++ src/main/main.c | 5 + src/main/mw.c | 5 +- src/main/telemetry/ltm.c | 1 + src/main/telemetry/smartport.c | 1 + 18 files changed, 547 insertions(+), 1 deletion(-) create mode 100644 src/main/drivers/vtx_rtc6705.c create mode 100644 src/main/drivers/vtx_rtc6705.h create mode 100644 src/main/io/vtx.c create mode 100644 src/main/io/vtx.h diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 97ca2b619e..9e8fdc1fd2 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -60,6 +60,7 @@ #include "io/serial_cli.h" #include "io/serial_msp.h" #include "io/statusindicator.h" +#include "io/vtx.h" #include "rx/rx.h" #include "rx/msp.h" diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 916b22ba25..0eeead3156 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -36,6 +36,7 @@ #include "io/escservo.h" #include "rx/rx.h" #include "io/rc_controls.h" +#include "io/vtx.h" #include "io/gimbal.h" #include "io/gps.h" diff --git a/src/main/config/config.c b/src/main/config/config.c index f7d1cb57a5..7a5d3d1539 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -54,6 +54,7 @@ #include "io/rc_curves.h" #include "io/ledstrip.h" #include "io/gps.h" +#include "io/vtx.h" #include "rx/rx.h" @@ -567,6 +568,13 @@ static void resetConf(void) masterConfig.ledstrip_visual_beeper = 0; #endif +#ifdef VTX + masterConfig.vtx_band = 4; //Fatshark/Airwaves + masterConfig.vtx_channel = 1; //CH1 + masterConfig.vtx_mode = 0; //CH+BAND mode + masterConfig.vtx_mhz = 5740; //F0 +#endif + #ifdef SPRACINGF3 featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 1; diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index ecc4af7ec8..ee3412202b 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -132,6 +132,15 @@ typedef struct master_t { modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT]; adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT]; +#ifdef VTX + uint8_t vtx_band; //1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Raceband + uint8_t vtx_channel; //1-8 + uint8_t vtx_mode; //0=ch+band 1=mhz + uint16_t vtx_mhz; //5740 + + vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT]; +#endif + #ifdef BLACKBOX uint8_t blackbox_rate_num; uint8_t blackbox_rate_denom; diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c new file mode 100644 index 0000000000..4bdaf9931d --- /dev/null +++ b/src/main/drivers/vtx_rtc6705.c @@ -0,0 +1,191 @@ +/* + * 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 . + */ + +/* + * Author: Giles Burgess (giles@multiflite.co.uk) + * + * This source code is provided as is and can be used/modified so long + * as this header is maintained with the file at all times. + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef VTX + +#include "common/maths.h" + +#include "drivers/vtx_rtc6705.h" +#include "drivers/bus_spi.h" +#include "drivers/system.h" + +#define RTC6705_SET_HEAD 0x3210 //fosc=8mhz r=400 +#define RTC6705_SET_A1 0x8F3031 //5865 +#define RTC6705_SET_A2 0x8EB1B1 //5845 +#define RTC6705_SET_A3 0x8E3331 //5825 +#define RTC6705_SET_A4 0x8DB4B1 //5805 +#define RTC6705_SET_A5 0x8D3631 //5785 +#define RTC6705_SET_A6 0x8CB7B1 //5765 +#define RTC6705_SET_A7 0x8C4131 //5745 +#define RTC6705_SET_A8 0x8BC2B1 //5725 +#define RTC6705_SET_B1 0x8BF3B1 //5733 +#define RTC6705_SET_B2 0x8C6711 //5752 +#define RTC6705_SET_B3 0x8CE271 //5771 +#define RTC6705_SET_B4 0x8D55D1 //5790 +#define RTC6705_SET_B5 0x8DD131 //5809 +#define RTC6705_SET_B6 0x8E4491 //5828 +#define RTC6705_SET_B7 0x8EB7F1 //5847 +#define RTC6705_SET_B8 0x8F3351 //5866 +#define RTC6705_SET_E1 0x8B4431 //5705 +#define RTC6705_SET_E2 0x8AC5B1 //5685 +#define RTC6705_SET_E3 0x8A4731 //5665 +#define RTC6705_SET_E4 0x89D0B1 //5645 +#define RTC6705_SET_E5 0x8FA6B1 //5885 +#define RTC6705_SET_E6 0x902531 //5905 +#define RTC6705_SET_E7 0x90A3B1 //5925 +#define RTC6705_SET_E8 0x912231 //5945 +#define RTC6705_SET_F1 0x8C2191 //5740 +#define RTC6705_SET_F2 0x8CA011 //5760 +#define RTC6705_SET_F3 0x8D1691 //5780 +#define RTC6705_SET_F4 0x8D9511 //5800 +#define RTC6705_SET_F5 0x8E1391 //5820 +#define RTC6705_SET_F6 0x8E9211 //5840 +#define RTC6705_SET_F7 0x8F1091 //5860 +#define RTC6705_SET_F8 0x8F8711 //5880 +#define RTC6705_SET_R1 0x8A2151 //5658 +#define RTC6705_SET_R2 0x8B04F1 //5695 +#define RTC6705_SET_R3 0x8BF091 //5732 +#define RTC6705_SET_R4 0x8CD431 //5769 +#define RTC6705_SET_R5 0x8DB7D1 //5806 +#define RTC6705_SET_R6 0x8EA371 //5843 +#define RTC6705_SET_R7 0x8F8711 //5880 +#define RTC6705_SET_R8 0x9072B1 //5917 + +#define RTC6705_SET_R 400 //Reference clock +#define RTC6705_SET_FDIV 1024 //128*(fosc/1000000) +#define RTC6705_SET_NDIV 16 //Remainder divider to get 'A' part of equation +#define RTC6705_SET_WRITE 0x11 //10001b to write to register +#define RTC6705_SET_DIVMULT 1000000 //Division value (to fit into a uint32_t) (Hz to MHz) + +#define DISABLE_RTC6705 GPIO_SetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN) +#define ENABLE_RTC6705 GPIO_ResetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN) + +// Define variables +static const uint32_t channelArray[RTC6705_BAND_MAX][RTC6705_CHANNEL_MAX] = { + { RTC6705_SET_A1, RTC6705_SET_A2, RTC6705_SET_A3, RTC6705_SET_A4, RTC6705_SET_A5, RTC6705_SET_A6, RTC6705_SET_A7, RTC6705_SET_A8 }, + { RTC6705_SET_B1, RTC6705_SET_B2, RTC6705_SET_B3, RTC6705_SET_B4, RTC6705_SET_B5, RTC6705_SET_B6, RTC6705_SET_B7, RTC6705_SET_B8 }, + { RTC6705_SET_E1, RTC6705_SET_E2, RTC6705_SET_E3, RTC6705_SET_E4, RTC6705_SET_E5, RTC6705_SET_E6, RTC6705_SET_E7, RTC6705_SET_E8 }, + { RTC6705_SET_F1, RTC6705_SET_F2, RTC6705_SET_F3, RTC6705_SET_F4, RTC6705_SET_F5, RTC6705_SET_F6, RTC6705_SET_F7, RTC6705_SET_F8 }, + { RTC6705_SET_R1, RTC6705_SET_R2, RTC6705_SET_R3, RTC6705_SET_R4, RTC6705_SET_R5, RTC6705_SET_R6, RTC6705_SET_R7, RTC6705_SET_R8 }, +}; + +/** + * Send a command and return if good + * TODO chip detect + */ +static bool rtc6705IsReady() +{ + // Sleep a little bit to make sure it has booted + delay(50); + + // TODO Do a read and get current config (note this would be reading on MOSI (data) line) + + return true; +} + +/** + * Reverse a uint32_t (LSB to MSB) + * This is easier for when generating the frequency to then + * reverse the bits afterwards + */ +static uint32_t reverse32(uint32_t in) { + uint32_t out = 0; + + for (uint8_t i = 0 ; i < 32 ; i++) + { + out |= ((in>>i) & 1)<<(31-i); + } + + return out; +} + +/** + * Start chip if available + */ +bool rtc6705Init() +{ + DISABLE_RTC6705; + spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); + return rtc6705IsReady(); +} + +/** + * Transfer a 25bit packet to RTC6705 + * This will just send it as a 32bit packet LSB meaning + * extra 0's get truncated on RTC6705 end + */ +static void rtc6705Transfer(uint32_t command) +{ + command = reverse32(command); + + ENABLE_RTC6705; + + spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 24) & 0xFF); + spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 16) & 0xFF); + spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 8) & 0xFF); + spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 0) & 0xFF); + + DISABLE_RTC6705; +} + +/** + * Set a band and channel + */ +void rtc6705SetChannel(uint8_t band, uint8_t channel) +{ + band = constrain(band, RTC6705_BAND_MIN, RTC6705_BAND_MAX); + channel = constrain(channel, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX); + + rtc6705Transfer(RTC6705_SET_HEAD); + rtc6705Transfer(channelArray[band-1][channel-1]); +} + + /** + * Set a freq in mhz + * Formula derived from datasheet + */ +void rtc6705SetFreq(uint16_t freq) +{ + freq = constrain(freq, RTC6705_FREQ_MIN, RTC6705_FREQ_MAX); + + uint32_t val_hex = 0; + + uint32_t val_a = ((((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers) + uint32_t val_n = (((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers) + + val_hex |= RTC6705_SET_WRITE; + val_hex |= (val_a << 5); + val_hex |= (val_n << 12); + + rtc6705Transfer(RTC6705_SET_HEAD); + rtc6705Transfer(val_hex); +} + +#endif diff --git a/src/main/drivers/vtx_rtc6705.h b/src/main/drivers/vtx_rtc6705.h new file mode 100644 index 0000000000..d72116659f --- /dev/null +++ b/src/main/drivers/vtx_rtc6705.h @@ -0,0 +1,38 @@ +/* + * 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 . + */ + +/* + * Author: Giles Burgess (giles@multiflite.co.uk) + * + * This source code is provided as is and can be used/modified so long + * as this header is maintained with the file at all times. + */ + +#pragma once + +#include + +#define RTC6705_BAND_MIN 1 +#define RTC6705_BAND_MAX 5 +#define RTC6705_CHANNEL_MIN 1 +#define RTC6705_CHANNEL_MAX 8 +#define RTC6705_FREQ_MIN 5600 +#define RTC6705_FREQ_MAX 5950 + +bool rtc6705Init(); +void rtc6705SetChannel(uint8_t band, uint8_t channel); +void rtc6705SetFreq(uint16_t freq); \ No newline at end of file diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 1448a6b5e1..f1ac9e3520 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -31,6 +31,7 @@ #include "sensors/sensors.h" #include "io/statusindicator.h" +#include "io/vtx.h" #ifdef GPS #include "io/gps.h" diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index cf85b7db37..afb78f3529 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -58,6 +58,7 @@ #include "io/gimbal.h" #include "io/serial.h" #include "io/gps.h" +#include "io/vtx.h" #include "flight/failsafe.h" #include "flight/mixer.h" diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index a72efd990e..8f25d6f6cb 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -49,6 +49,7 @@ #include "io/escservo.h" #include "io/rc_controls.h" #include "io/rc_curves.h" +#include "io/vtx.h" #include "io/display.h" @@ -304,6 +305,21 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat } #endif +#ifdef VTX + if (rcSticks == THR_HI + YAW_LO + PIT_CE + ROL_HI) { + vtxIncrementBand(); + } + if (rcSticks == THR_HI + YAW_LO + PIT_CE + ROL_LO) { + vtxDecrementBand(); + } + if (rcSticks == THR_HI + YAW_HI + PIT_CE + ROL_HI) { + vtxIncrementChannel(); + } + if (rcSticks == THR_HI + YAW_HI + PIT_CE + ROL_LO) { + vtxDecrementChannel(); + } +#endif + } bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationConditions, boxId_e modeId) diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h index 8cbb078a4d..0f107e403d 100644 --- a/src/main/io/rc_controls.h +++ b/src/main/io/rc_controls.h @@ -161,6 +161,7 @@ bool areSticksInApModePosition(uint16_t ap_mode); throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle); void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch); +bool isRangeActive(uint8_t auxChannelIndex, channelRange_t *range); void updateActivatedModes(modeActivationCondition_t *modeActivationConditions); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index ea6801e079..7cc6ae32f6 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -60,6 +60,7 @@ #include "io/flashfs.h" #include "io/beeper.h" #include "io/asyncfatfs/asyncfatfs.h" +#include "io/vtx.h" #include "rx/rx.h" #include "rx/spektrum.h" @@ -164,6 +165,10 @@ static void cliFlashRead(char *cmdline); #endif #endif +#ifdef VTX +static void cliVtx(char *cmdline); +#endif + #ifdef USE_SDCARD static void cliSdInfo(char *cmdline); #endif @@ -326,6 +331,9 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n" "\t<+|->[name]", cliBeeper), #endif +#ifdef VTX + CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx), +#endif }; #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t)) @@ -768,6 +776,13 @@ const clivalue_t valueTable[] = { { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } }, #endif +#ifdef VTX + { "vtx_band", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_band, .config.minmax = { 1, 5 } }, + { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 1, 8 } }, + { "vtx_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_mode, .config.minmax = { 0, 2 } }, + { "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } }, +#endif + { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } }, { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } }, { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } }, @@ -1773,6 +1788,67 @@ static void cliFlashRead(char *cmdline) #endif #endif +#ifdef VTX +static void cliVtx(char *cmdline) +{ + int i, val = 0; + char *ptr; + + if (isEmpty(cmdline)) { + // print out vtx channel settings + for (i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) { + vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i]; + printf("vtx %u %u %u %u %u %u\r\n", + i, + cac->auxChannelIndex, + cac->band, + cac->channel, + MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep), + MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep) + ); + } + } else { + ptr = cmdline; + i = atoi(ptr++); + if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) { + vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i]; + uint8_t validArgumentCount = 0; + ptr = strchr(ptr, ' '); + if (ptr) { + val = atoi(++ptr); + if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) { + cac->auxChannelIndex = val; + validArgumentCount++; + } + } + ptr = strchr(ptr, ' '); + if (ptr) { + val = atoi(++ptr); + if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) { + cac->band = val; + validArgumentCount++; + } + } + ptr = strchr(ptr, ' '); + if (ptr) { + val = atoi(++ptr); + if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) { + cac->channel = val; + validArgumentCount++; + } + } + ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount); + + if (validArgumentCount != 5) { + memset(cac, 0, sizeof(vtxChannelActivationCondition_t)); + } + } else { + cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1); + } + } +} +#endif + static void dumpValues(uint16_t valueSection) { uint32_t i; @@ -1963,6 +2039,12 @@ static void cliDump(char *cmdline) } #endif +#ifdef VTX + cliPrint("\r\n# vtx\r\n"); + + cliVtx(""); +#endif + printSectionBreak(); dumpValues(MASTER_VALUE); diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index a65b224b86..f932fdb80a 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -57,6 +57,7 @@ #include "io/flashfs.h" #include "io/transponder_ir.h" #include "io/asyncfatfs/asyncfatfs.h" +#include "io/vtx.h" #include "telemetry/telemetry.h" diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c new file mode 100644 index 0000000000..3a48bc1a67 --- /dev/null +++ b/src/main/io/vtx.c @@ -0,0 +1,146 @@ +/* + * 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 . + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef VTX + +#include "common/color.h" +#include "common/axis.h" +#include "common/maths.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/gpio.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" +#include "config/runtime_config.h" + +static uint8_t locked = 0; + +void vtxInit() +{ + rtc6705Init(); + if (masterConfig.vtx_mode == 0) { + rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel); + } else if (masterConfig.vtx_mode == 1) { + rtc6705SetFreq(masterConfig.vtx_mhz); + } +} + +static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_t min, int32_t max) +{ + if (ARMING_FLAG(ARMED)) { + locked = 1; + } + + if (masterConfig.vtx_mode == 0 && !locked) { + uint8_t temp = (*bandOrChannel) + step; + temp = constrain(temp, min, max); + *bandOrChannel = temp; + + rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel); + writeEEPROM(); + readEEPROM(); + beeperConfirmationBeeps(temp); + } +} + +void vtxIncrementBand() +{ + setChannelSaveAndNotify(&(masterConfig.vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX); +} + +void vtxDecrementBand() +{ + setChannelSaveAndNotify(&(masterConfig.vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX); +} + +void vtxIncrementChannel() +{ + setChannelSaveAndNotify(&(masterConfig.vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX); +} + +void vtxDecrementChannel() +{ + setChannelSaveAndNotify(&(masterConfig.vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX); +} + +void vtxUpdateActivatedChannel() +{ + if (ARMING_FLAG(ARMED)) { + locked = 1; + } + + if (masterConfig.vtx_mode == 2 && !locked) { + static uint8_t lastIndex = -1; + uint8_t index; + + for (index = 0; index < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; index++) { + vtxChannelActivationCondition_t *vtxChannelActivationCondition = &masterConfig.vtxChannelActivationConditions[index]; + + if (isRangeActive(vtxChannelActivationCondition->auxChannelIndex, &vtxChannelActivationCondition->range) + && index != lastIndex) { + lastIndex = index; + rtc6705SetChannel(vtxChannelActivationCondition->band, vtxChannelActivationCondition->channel); + break; + } + } + } +} + +#endif \ No newline at end of file diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h new file mode 100644 index 0000000000..ddcd7492de --- /dev/null +++ b/src/main/io/vtx.h @@ -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 . + */ + +#pragma once + +#include "drivers/vtx_rtc6705.h" + +#define VTX_BAND_MIN 1 +#define VTX_BAND_MAX 5 +#define VTX_CHANNEL_MIN 1 +#define VTX_CHANNEL_MAX 8 +#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10 + +typedef struct vtxChannelActivationCondition_s { + uint8_t auxChannelIndex; + uint8_t band; + uint8_t channel; + channelRange_t range; +} vtxChannelActivationCondition_t; + +void vtxInit(); +void vtxIncrementBand(); +void vtxDecrementBand(); +void vtxIncrementChannel(); +void vtxDecrementChannel(); +void vtxUpdateActivatedChannel(); \ No newline at end of file diff --git a/src/main/main.c b/src/main/main.c index 0172dc2ebd..d89bb44923 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -70,6 +70,7 @@ #include "io/display.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/transponder_ir.h" +#include "io/vtx.h" #include "sensors/sensors.h" #include "sensors/sonar.h" @@ -397,6 +398,10 @@ void init(void) #endif #endif +#ifdef VTX + vtxInit(); +#endif + #ifdef USE_HARDWARE_REVISION_DETECTION updateHardwareRevision(); #endif diff --git a/src/main/mw.c b/src/main/mw.c index 54401519b6..c5c5e0af5f 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -65,7 +65,7 @@ #include "io/statusindicator.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/transponder_ir.h" - +#include "io/vtx.h" #include "rx/rx.h" #include "rx/msp.h" @@ -629,6 +629,9 @@ void processRx(void) } #endif +#ifdef VTX + vtxUpdateActivatedChannel(); +#endif } void subTaskPidController(void) diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 0f2f1d12f8..ad184b5aa6 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -62,6 +62,7 @@ #include "io/gps.h" #include "io/ledstrip.h" #include "io/beeper.h" +#include "io/vtx.h" #include "rx/rx.h" diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index f9060539bd..47685ab0a8 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -37,6 +37,7 @@ #include "io/gimbal.h" #include "io/serial.h" #include "io/ledstrip.h" +#include "io/vtx.h" #include "sensors/boardalignment.h" #include "sensors/sensors.h" From 0a3bf6e991a4f70d72ad3629893ca8494ae6ec1a Mon Sep 17 00:00:00 2001 From: sblakemore Date: Wed, 2 Dec 2015 08:55:15 +1000 Subject: [PATCH 66/85] Add SINGULARITY target --- Makefile | 20 +- src/main/config/config.c | 15 +- src/main/drivers/pwm_mapping.c | 62 +++ src/main/drivers/timer.c | 25 ++ src/main/sensors/initialisation.c | 13 + .../target/SINGULARITY/system_stm32f30x.c | 372 ++++++++++++++++++ .../target/SINGULARITY/system_stm32f30x.h | 76 ++++ src/main/target/SINGULARITY/target.h | 131 ++++++ 8 files changed, 710 insertions(+), 4 deletions(-) create mode 100644 src/main/target/SINGULARITY/system_stm32f30x.c create mode 100644 src/main/target/SINGULARITY/system_stm32f30x.h create mode 100644 src/main/target/SINGULARITY/target.h diff --git a/Makefile b/Makefile index 58a284d0ca..7156073f0d 100644 --- a/Makefile +++ b/Makefile @@ -46,7 +46,7 @@ FORKNAME = betaflight CC3D_TARGETS = CC3D CC3D_OPBL -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY # Valid targets for OP VCP support VCP_VALID_TARGETS = $(CC3D_TARGETS) @@ -56,9 +56,9 @@ OPBL_VALID_TARGETS = CC3D_OPBL 64K_TARGETS = CJMCU 128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI -256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE +256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY -F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE +F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY # note that there is no hardfault debugging startup file assembly handler for other platforms ifeq ($(DEBUG_HARDFAULTS),F3) @@ -794,6 +794,20 @@ SPRACINGF3MINI_SRC = \ $(VCP_SRC) # $(FATFS_SRC) +SINGULARITY_SRC = \ + $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/serial_usb_vcp.c \ + io/flashfs.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) + # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src diff --git a/src/main/config/config.c b/src/main/config/config.c index 7a5d3d1539..081cf9e8d2 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -384,7 +384,7 @@ static void resetConf(void) masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerMode = MIXER_QUADX; featureClearAll(); -#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) +#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY) featureSet(FEATURE_RX_PPM); #endif @@ -692,6 +692,19 @@ static void resetConf(void) masterConfig.customMotorMixer[7].yaw = -1.0f; #endif + // alternative defaults settings for SINGULARITY target +#if defined(SINGULARITY) + featureSet(FEATURE_BLACKBOX); + masterConfig.blackbox_device = 1; + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; + + masterConfig.batteryConfig.vbatscale = 77; + + featureSet(FEATURE_RX_SERIAL); + masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; +#endif + // copy first profile into remaining profile for (i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index b95efed1da..b786ba0cee 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -577,6 +577,62 @@ static const uint16_t airPWM[] = { }; #endif +#if defined(SINGULARITY) +static const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t multiPWM[] = { + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t airPWM[] = { + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; +#endif + #ifdef SPRACINGF3MINI static const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input @@ -875,6 +931,12 @@ if (init->useBuzzerP6) { if (timerIndex == PWM7 || timerIndex == PWM8) type = MAP_TO_SERVO_OUTPUT; #endif + +#if defined(SINGULARITY) + // remap PWM6+7 as servos + if (timerIndex == PWM6 || timerIndex == PWM7) + type = MAP_TO_SERVO_OUTPUT; +#endif } if (init->useChannelForwarding && !init->airplane) { diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index f0a8ea9600..bc52c6e3cc 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -391,6 +391,31 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { #endif +#ifdef SINGULARITY +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, GPIOA, Pin_15, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1}, // PPM/SERIAL RX + + { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 + { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2}, // PWM2 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM3 + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM4 + { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_1}, // PWM5 + { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_1}, // PWM6 + + { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // SOFTSERIAL1 RX (NC) + { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // SOFTSERIAL1 TX + + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // LED_STRIP +}; + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17)) + +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3) +#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) + +#endif + #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS) #define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4 diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 7e05f9688a..ab9b27c898 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -182,6 +182,19 @@ const extiConfig_t *selectMPUIntExtiConfig(void) return &MotolabF3MPU6050Config; #endif +#ifdef SINGULARITY + static const extiConfig_t singularityMPU6050Config = { + .gpioAHBPeripherals = RCC_AHBPeriph_GPIOC, + .gpioPort = GPIOC, + .gpioPin = Pin_13, + .exti_port_source = EXTI_PortSourceGPIOC, + .exti_pin_source = EXTI_PinSource13, + .exti_line = EXTI_Line13, + .exti_irqn = EXTI15_10_IRQn + }; + return &singularityMPU6050Config; +#endif + #ifdef ALIENFLIGHTF3 // MPU_INT output on V1 PA15 static const extiConfig_t alienFlightF3V1MPUIntExtiConfig = { diff --git a/src/main/target/SINGULARITY/system_stm32f30x.c b/src/main/target/SINGULARITY/system_stm32f30x.c new file mode 100644 index 0000000000..fca6969825 --- /dev/null +++ b/src/main/target/SINGULARITY/system_stm32f30x.c @@ -0,0 +1,372 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.c + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F30x devices, + * and is generated by the clock configuration tool + * stm32f30x_Clock_Configuration_V1.0.0.xls + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f30x.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f30x.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and HSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define + * in "stm32f30x.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + * Supported STM32F30x device + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *---------------------------------------------------------------------------- + * PLLMUL | 9 + *----------------------------------------------------------------------------- + * PREDIV | 1 + *----------------------------------------------------------------------------- + * USB Clock | ENABLE + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 2 + *----------------------------------------------------------------------------- + * Prefetch Buffer | ON + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f30x_system + * @{ + */ + +/** @addtogroup STM32F30x_System_Private_Includes + * @{ + */ + +#include "stm32f30x.h" + +uint32_t hse_value = HSE_VALUE; + +/** + * @} + */ + +/* Private typedef -----------------------------------------------------------*/ + +/** @addtogroup STM32F30x_System_Private_Defines + * @{ + */ +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ + +/** @addtogroup STM32F30x_System_Private_Variables + * @{ + */ + + uint32_t SystemCoreClock = 72000000; + + __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +/** + * @} + */ + +/** @addtogroup STM32F30x_System_Private_FunctionPrototypes + * @{ + */ + +void SetSysClock(void); + +/** + * @} + */ + +/** @addtogroup STM32F30x_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemFrequency variable. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* FPU settings ------------------------------------------------------------*/ + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ + #endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR &= 0xF87FC00C; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + + /* Reset PREDIV1[3:0] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFFFF0; + + /* Reset USARTSW[1:0], I2CSW and TIMs bits */ + RCC->CFGR3 &= (uint32_t)0xFF00FCCC; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + + /* Configure the System clock source, PLL Multiplier and Divider factors, + AHB/APBx prescalers and Flash settings ----------------------------------*/ + //SetSysClock(); // called from main() + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + { + prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + } + break; + default: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ +void SetSysClock(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer and set Flash Latency */ + FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1; + + /* HCLK = SYSCLK / 1 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK / 1 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK / 2 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + + /* PLL configuration */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9); + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/src/main/target/SINGULARITY/system_stm32f30x.h b/src/main/target/SINGULARITY/system_stm32f30x.h new file mode 100644 index 0000000000..4f999d3058 --- /dev/null +++ b/src/main/target/SINGULARITY/system_stm32f30x.h @@ -0,0 +1,76 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.h + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f30x_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F30X_H +#define __SYSTEM_STM32F30X_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/** @addtogroup STM32F30x_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F30X_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h new file mode 100644 index 0000000000..052aaa7c22 --- /dev/null +++ b/src/main/target/SINGULARITY/target.h @@ -0,0 +1,131 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SING" + +#define LED0_GPIO GPIOB +#define LED0_PIN Pin_3 +#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB + +#define BEEP_GPIO GPIOC +#define BEEP_PIN Pin_15 +#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC + +#define USABLE_TIMER_CHANNEL_COUNT 10 + +#define USE_MPU_DATA_READY_SIGNAL + +#define GYRO +#define USE_GYRO_MPU6050 +#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP + +#define ACC +#define USE_ACC_MPU6050 +#define ACC_MPU6050_ALIGN CW0_DEG_FLIP + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define BEEPER +#define LED0 + +#define USE_VCP +#define USE_USART1 // JST-SH Serial - TX (PA9) RX (PA10) +#define USE_USART2 // Input - TX (NC) RX (PA15) +#define USE_USART3 // Solder Pads - TX (PB10) RX (PB11) +#define USE_SOFTSERIAL1 // Telemetry +#define SERIAL_PORT_COUNT 5 + +#define UART1_TX_PIN GPIO_Pin_9 +#define UART1_RX_PIN GPIO_Pin_10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 + +#define UART2_TX_PIN GPIO_Pin_14 //Not connected +#define UART2_RX_PIN GPIO_Pin_15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource14 +#define UART2_RX_PINSOURCE GPIO_PinSource15 + +#define UART3_TX_PIN GPIO_Pin_10 +#define UART3_RX_PIN GPIO_Pin_11 +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 + +#define SOFTSERIAL_1_TIMER TIM15 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 7 //Not connected +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 8 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define M25P16_CS_GPIO GPIOB +#define M25P16_CS_PIN GPIO_Pin_12 +#define M25P16_SPI_INSTANCE SPI2 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC2 +#define ADC_DMA_CHANNEL DMA2_Channel1 +#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 + +#define VBAT_ADC_GPIO GPIOB +#define VBAT_ADC_GPIO_PIN GPIO_Pin_2 +#define VBAT_ADC_CHANNEL ADC_Channel_12 + +#define LED_STRIP +#define LED_STRIP_TIMER TIM1 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_6 +#define WS2811_PIN GPIO_Pin_8 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM1 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define AUTOTUNE +#define BLACKBOX +#define TELEMETRY +#define SERIAL_RX +#define GPS +#define USE_SERVOS +#define USE_CLI + +#define SPEKTRUM_BIND +// USART2, PA15 +#define BIND_PORT GPIOA +#define BIND_PIN Pin_15 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + From ddee07518943e6c3641302267b2376300908f669 Mon Sep 17 00:00:00 2001 From: sblakemore Date: Fri, 27 May 2016 07:07:19 +1000 Subject: [PATCH 67/85] Add VTX support to SINGULARITY --- Makefile | 2 ++ src/main/target/SINGULARITY/target.h | 6 ++++++ 2 files changed, 8 insertions(+) diff --git a/Makefile b/Makefile index 7156073f0d..e5a4916594 100644 --- a/Makefile +++ b/Makefile @@ -803,7 +803,9 @@ SINGULARITY_SRC = \ drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_softserial.c \ drivers/serial_usb_vcp.c \ + drivers/vtx_rtc6705.c \ io/flashfs.c \ + io/vtx.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ $(VCP_SRC) diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 052aaa7c22..54d1824444 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -81,8 +81,14 @@ #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI +#define USE_SPI_DEVICE_1 // PA4, 5, 6, 7 #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 +#define VTX +#define RTC6705_CS_GPIO GPIOA +#define RTC6705_CS_PIN GPIO_Pin_4 +#define RTC6705_SPI_INSTANCE SPI1 + #define M25P16_CS_GPIO GPIOB #define M25P16_CS_PIN GPIO_Pin_12 #define M25P16_SPI_INSTANCE SPI2 From f3b9f65c8b0075843d53d678dc2a5a5f3cbab9ad Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 31 May 2016 11:50:45 +0200 Subject: [PATCH 68/85] Add singularity to autobuild --- fake_travis_build.sh | 3 ++- top_makefile | 2 ++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 9d1fe66169..7749d64354 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -16,7 +16,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=IRCFUSIONF3" \ "TARGET=ALIENFLIGHTF1" \ "TARGET=ALIENFLIGHTF3" \ - "TARGET=DOGE") + "TARGET=DOGE" \ + "TARGET=SINGULARITY") #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/top_makefile b/top_makefile index d765dcf35b..4b1bb90e78 100644 --- a/top_makefile +++ b/top_makefile @@ -14,6 +14,7 @@ ALL_TARGETS += rmdo ALL_TARGETS += ircfusionf3 ALL_TARGETS += afromini ALL_TARGETS += doge +ALL_TARGETS += singularity CLEAN_TARGETS := $(addprefix clean_, $(ALL_TARGETS)) @@ -33,6 +34,7 @@ clean_rmdo rmdo : opts := TARGET=RMDO clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3 clean_afromini afromini : opts := TARGET=AFROMINI clean_doge doge : opts := TARGET=DOGE +clean_singularity singularity : opts := TARGET=SINGULARITY .PHONY: all clean From 39763abe0b47a5f72c3a4753f569b02fafe1e569 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 31 May 2016 12:38:50 +0200 Subject: [PATCH 69/85] Remove RC Rate influence on superExpo curve --- src/main/flight/pid.c | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 783c627ec2..8058cd34dc 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -74,16 +74,15 @@ void setTargetPidLooptime(uint8_t pidProcessDenom) { targetPidLooptime = targetLooptime * pidProcessDenom; } -float calculateExpoPlus(int axis, const rxConfig_t *rxConfig) { - float propFactor; - float superExpoFactor; +float calculateExpoPlus(int axis, const rxConfig_t *rxConfig, const controlRateConfig_t *controlRateConfig) { + float propFactor, superExpoFactor, rcFactor; if (axis == YAW && !rxConfig->superExpoYawMode) { propFactor = 1.0f; } else { - float rcFactor = (ABS(rcCommand[axis]) / 500.0f); - superExpoFactor = (axis == YAW) ? rxConfig->superExpoFactorYaw : rxConfig->superExpoFactor; + rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); + propFactor = constrainf(1.0f - ((superExpoFactor / 100.0f) * rcFactor * rcFactor * rcFactor), 0.0f, 1.0f); } @@ -210,7 +209,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // -----calculate P component if ((isSuperExpoActive() && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { - PTerm = (luxPTermScale * kP * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig)); + PTerm = (luxPTermScale * kP * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig, controlRateConfig)); } else { PTerm = luxPTermScale * RateError * kP * tpaFactor; } @@ -335,7 +334,7 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // -----calculate P component if ((isSuperExpoActive() && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { - PTerm = (kP * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig))) >> 7; + PTerm = (kP * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig, controlRateConfig))) >> 7; } else { PTerm = (RateError * kP * PIDweight[axis] / 100) >> 7; } From d4c22f1c28e54420681362df6a90616932982d31 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 31 May 2016 22:30:47 +0200 Subject: [PATCH 70/85] Rework Super Expo Rate Implementation // On the fly Rc Expo --- src/main/blackbox/blackbox.c | 70 +++++++++++------------- src/main/config/config.c | 13 ++--- src/main/flight/pid.c | 102 +++++++++++++++-------------------- src/main/io/rc_controls.c | 4 +- src/main/io/rc_curves.c | 40 +++----------- src/main/io/rc_curves.h | 6 +-- src/main/io/serial_cli.c | 3 -- src/main/io/serial_msp.c | 6 +-- src/main/mw.c | 4 +- src/main/rx/rx.h | 3 -- 10 files changed, 91 insertions(+), 160 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 9e8fdc1fd2..bf43dcc35f 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1195,146 +1195,140 @@ static bool blackboxWriteSysinfo() case 18: blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); break; - case 19: - blackboxPrintfHeaderLine("superExpoFactor:%d, %d", masterConfig.rxConfig.superExpoFactor, masterConfig.rxConfig.superExpoFactorYaw); - break; - case 20: + case 21: blackboxPrintfHeaderLine("rates:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); break; - case 21: + case 22: blackboxPrintfHeaderLine("looptime:%d", targetLooptime); break; - case 22: + case 23: blackboxPrintfHeaderLine("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); break; - case 23: + case 24: blackboxPrintfHeaderLine("rollPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); break; - case 24: + case 25: blackboxPrintfHeaderLine("pitchPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); break; - case 25: + case 26: blackboxPrintfHeaderLine("yawPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); break; - case 26: + case 27: blackboxPrintfHeaderLine("altPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); break; - case 27: + case 28: blackboxPrintfHeaderLine("posPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); break; - case 28: + case 29: blackboxPrintfHeaderLine("posrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); break; - case 29: + case 30: blackboxPrintfHeaderLine("navrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); break; - case 30: + case 31: blackboxPrintfHeaderLine("levelPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); break; - case 31: + case 32: blackboxPrintfHeaderLine("magPID:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); break; - case 32: + case 33: blackboxPrintfHeaderLine("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); break; - case 33: + case 34: blackboxPrintfHeaderLine("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); break; - case 34: + case 35: blackboxPrintfHeaderLine("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); break; - case 35: + case 36: blackboxPrintfHeaderLine("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); break; - case 36: + case 37: blackboxPrintfHeaderLine("dynamic_pid:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); break; - case 37: + case 38: blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); break; - case 38: + case 39: blackboxPrintfHeaderLine("yawItermResetRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); break; - case 39: + case 40: blackboxPrintfHeaderLine("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); break; - case 40: + case 41: blackboxPrintfHeaderLine("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold); break; - case 41: + case 42: blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); break; - case 42: + case 43: blackboxPrintfHeaderLine("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); break; - case 43: + case 44: blackboxPrintfHeaderLine("gyro_lpf:%d", masterConfig.gyro_lpf); break; - case 44: + case 45: blackboxPrintfHeaderLine("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); break; - case 45: + case 46: blackboxPrintfHeaderLine("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); break; - case 46: + case 47: blackboxPrintfHeaderLine("acc_hardware:%d", masterConfig.acc_hardware); break; - case 47: + case 48: blackboxPrintfHeaderLine("baro_hardware:%d", masterConfig.baro_hardware); break; - case 48: + case 49: blackboxPrintfHeaderLine("mag_hardware:%d", masterConfig.mag_hardware); break; - case 49: + case 50: blackboxPrintfHeaderLine("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); break; - case 50: + case 51: blackboxPrintfHeaderLine("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); break; - case 51: - blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); - break; case 52: - blackboxPrintfHeaderLine("superExpoYawMode:%d", masterConfig.rxConfig.superExpoYawMode); + blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); break; case 53: blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures); diff --git a/src/main/config/config.c b/src/main/config/config.c index 081cf9e8d2..88fd490592 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -141,7 +141,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 138; +static const uint8_t EEPROM_CONF_VERSION = 139; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -310,15 +310,15 @@ void resetSerialConfig(serialConfig_t *serialConfig) static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcRate8 = 100; - controlRateConfig->rcExpo8 = 70; + controlRateConfig->rcExpo8 = 10; controlRateConfig->thrMid8 = 50; controlRateConfig->thrExpo8 = 0; controlRateConfig->dynThrPID = 20; - controlRateConfig->rcYawExpo8 = 20; + controlRateConfig->rcYawExpo8 = 10; controlRateConfig->tpa_breakpoint = 1650; for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) { - controlRateConfig->rates[axis] = 50; + controlRateConfig->rates[axis] = 70; } } @@ -460,10 +460,7 @@ static void resetConf(void) masterConfig.rxConfig.rcSmoothing = 0; masterConfig.rxConfig.fpvCamAngleDegrees = 0; masterConfig.rxConfig.max_aux_channel = 6; - masterConfig.rxConfig.superExpoFactor = 30; masterConfig.rxConfig.airModeActivateThreshold = 1350; - masterConfig.rxConfig.superExpoFactorYaw = 40; - masterConfig.rxConfig.superExpoYawMode = 1; resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges); @@ -746,8 +743,6 @@ static bool isEEPROMContentValid(void) void activateControlRateConfig(void) { - generatePitchRollCurve(currentControlRateProfile); - generateYawCurve(currentControlRateProfile); generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig); } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 8058cd34dc..8dc3f28f1f 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -74,19 +74,19 @@ void setTargetPidLooptime(uint8_t pidProcessDenom) { targetPidLooptime = targetLooptime * pidProcessDenom; } -float calculateExpoPlus(int axis, const rxConfig_t *rxConfig, const controlRateConfig_t *controlRateConfig) { - float propFactor, superExpoFactor, rcFactor; +float calculateRate(int axis, const controlRateConfig_t *controlRateConfig) { + float angleRate; - if (axis == YAW && !rxConfig->superExpoYawMode) { - propFactor = 1.0f; + if (isSuperExpoActive()) { + float rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); + rcFactor = 1.0f / (1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f))); + + angleRate = rcFactor * ((27 * rcCommand[axis]) / 16.0f); } else { - superExpoFactor = (axis == YAW) ? rxConfig->superExpoFactorYaw : rxConfig->superExpoFactor; - rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); - - propFactor = constrainf(1.0f - ((superExpoFactor / 100.0f) * rcFactor * rcFactor * rcFactor), 0.0f, 1.0f); + angleRate = (float)((controlRateConfig->rates[axis] + 27) * rcCommand[axis]) / 16.0f; } - return propFactor; + return angleRate; } uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) { @@ -169,31 +169,26 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // ----------PID controller---------- for (axis = 0; axis < 3; axis++) { - uint8_t rate = controlRateConfig->rates[axis]; - if (axis == FD_YAW) { - // YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate - AngleRate = (float)((rate + 47) * rcCommand[YAW]) / 32.0f; - } else { - // ACRO mode, control is GYRO based, direct sticks control is applied to rate PID - AngleRate = (float)((rate + 27) * rcCommand[axis]) / 16.0f; // 200dps to 1200dps max roll/pitch rate - if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { - // calculate error angle and limit the angle to the max inclination + // ACRO mode, control is GYRO based, direct sticks control is applied to rate PID + AngleRate = calculateRate(axis, controlRateConfig); + + if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { + // calculate error angle and limit the angle to the max inclination #ifdef GPS - const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here + const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), + +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here #else - const float errorAngle = (constrain(2 * rcCommand[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here + const float errorAngle = (constrain(2 * rcCommand[axis], -((int) max_angle_inclination), + +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]); // 16 bits is ok here #endif - if (FLIGHT_MODE(ANGLE_MODE)) { - // ANGLE mode - control is angle based, so control loop is needed - AngleRate = errorAngle * pidProfile->P8[PIDLEVEL] / 16.0f; - } else { - // HORIZON mode - direct sticks control is applied to rate PID - // mix up angle error to desired AngleRate to add a little auto-level feel - AngleRate += errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 16.0f; - } + if (FLIGHT_MODE(ANGLE_MODE)) { + // ANGLE mode - control is angle based, so control loop is needed + AngleRate = errorAngle * pidProfile->P8[PIDLEVEL] / 16.0f; + } else { + // HORIZON mode - direct sticks control is applied to rate PID + // mix up angle error to desired AngleRate to add a little auto-level feel + AngleRate += errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 16.0f; } } @@ -208,11 +203,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ uint16_t kP = (pidProfile->dynamic_pid) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; // -----calculate P component - if ((isSuperExpoActive() && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { - PTerm = (luxPTermScale * kP * tpaFactor) * (AngleRate - gyroRate * calculateExpoPlus(axis, rxConfig, controlRateConfig)); - } else { - PTerm = luxPTermScale * RateError * kP * tpaFactor; - } + PTerm = luxPTermScale * RateError * kP * tpaFactor; // Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) { @@ -295,31 +286,26 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // ----------PID controller---------- for (axis = 0; axis < 3; axis++) { - uint8_t rate = controlRateConfig->rates[axis]; // -----Get the desired angle rate depending on flight mode - if (axis == FD_YAW) { - // YAW is always gyro-controlled (MAG correction is applied to rcCommand) - AngleRateTmp = ((int32_t)(rate + 47) * rcCommand[YAW]) >> 5; - } else { - AngleRateTmp = ((int32_t)(rate + 27) * rcCommand[axis]) >> 4; - if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { - // calculate error angle and limit the angle to max configured inclination + AngleRateTmp = (int32_t)calculateRate(axis, controlRateConfig); + + if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { + // calculate error angle and limit the angle to max configured inclination #ifdef GPS - const int32_t errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]; + const int32_t errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), + +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]; #else - const int32_t errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]; + const int32_t errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination), + +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]; #endif - if (FLIGHT_MODE(ANGLE_MODE)) { - // ANGLE mode - control is angle based, so control loop is needed - AngleRateTmp = (errorAngle * pidProfile->P8[PIDLEVEL]) >> 4; - } else { - // HORIZON mode - mix up angle error to desired AngleRateTmp to add a little auto-level feel, - // horizonLevelStrength is scaled to the stick input - AngleRateTmp += (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 100) >> 4; - } + if (FLIGHT_MODE(ANGLE_MODE)) { + // ANGLE mode - control is angle based, so control loop is needed + AngleRateTmp = (errorAngle * pidProfile->P8[PIDLEVEL]) >> 4; + } else { + // HORIZON mode - mix up angle error to desired AngleRateTmp to add a little auto-level feel, + // horizonLevelStrength is scaled to the stick input + AngleRateTmp += (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 100) >> 4; } } @@ -333,11 +319,7 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate uint16_t kP = (pidProfile->dynamic_pid) ? getDynamicKp(axis, pidProfile) : pidProfile->P8[axis]; // -----calculate P component - if ((isSuperExpoActive() && axis != YAW) || (axis == YAW && rxConfig->superExpoYawMode == SUPEREXPO_YAW_ALWAYS)) { - PTerm = (kP * PIDweight[axis] / 100) * (AngleRateTmp - (int32_t)(gyroRate * calculateExpoPlus(axis, rxConfig, controlRateConfig))) >> 7; - } else { - PTerm = (RateError * kP * PIDweight[axis] / 100) >> 7; - } + PTerm = (RateError * kP * PIDweight[axis] / 100) >> 7; // Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply if((motorCount >= 4 && pidProfile->yaw_p_limit) && axis == YAW) { diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 8f25d6f6cb..4e7344ac9b 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -76,7 +76,7 @@ bool isAirmodeActive(void) { } bool isSuperExpoActive(void) { - return (IS_RC_MODE_ACTIVE(BOXSUPEREXPO) || feature(FEATURE_SUPEREXPO)); + return (feature(FEATURE_SUPEREXPO)); } void blackboxLogInflightAdjustmentEvent(adjustmentFunction_e adjustmentFunction, int32_t newValue) { @@ -503,13 +503,11 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm case ADJUSTMENT_RC_RATE: newValue = constrain((int)controlRateConfig->rcRate8 + delta, 0, 250); // FIXME magic numbers repeated in serial_cli.c controlRateConfig->rcRate8 = newValue; - generatePitchRollCurve(controlRateConfig); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RC_RATE, newValue); break; case ADJUSTMENT_RC_EXPO: newValue = constrain((int)controlRateConfig->rcExpo8 + delta, 0, 100); // FIXME magic numbers repeated in serial_cli.c controlRateConfig->rcExpo8 = newValue; - generatePitchRollCurve(controlRateConfig); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RC_EXPO, newValue); break; case ADJUSTMENT_THROTTLE_EXPO: diff --git a/src/main/io/rc_curves.c b/src/main/io/rc_curves.c index ac6e675790..2ed3919747 100644 --- a/src/main/io/rc_curves.c +++ b/src/main/io/rc_curves.c @@ -26,37 +26,9 @@ #include "config/config.h" -#define PITCH_LOOKUP_LENGTH 31 -#define YAW_LOOKUP_LENGTH 31 #define THROTTLE_LOOKUP_LENGTH 12 - -static int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL -static int16_t lookupYawRC[YAW_LOOKUP_LENGTH]; // lookup table for expo & RC rate YAW static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE - -void generatePitchRollCurve(controlRateConfig_t *controlRateConfig) -{ - uint8_t i; - float j = 0; - - for (i = 0; i < PITCH_LOOKUP_LENGTH; i++) { - lookupPitchRollRC[i] = (2500 + controlRateConfig->rcExpo8 * (j * j - 25)) * j * (int32_t) controlRateConfig->rcRate8 / 2500; - j += 0.2f; - } -} - -void generateYawCurve(controlRateConfig_t *controlRateConfig) -{ - uint8_t i; - float j = 0; - - for (i = 0; i < YAW_LOOKUP_LENGTH; i++) { - lookupYawRC[i] = (2500 + controlRateConfig->rcYawExpo8 * (j * j - 25)) * j / 25; - j += 0.2f; - } -} - void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig) { uint8_t i; @@ -74,16 +46,16 @@ void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoCo } } -int16_t rcLookupPitchRoll(int32_t tmp) +int16_t rcLookupPitchRoll(int32_t tmp, controlRateConfig_t *controlRateConfig) { - const int32_t tmp2 = tmp / 20; - return lookupPitchRollRC[tmp2] + (tmp - tmp2 * 20) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 20; + float tmpf = tmp / 100.0f; + return (int16_t)((2500.0f + (float)controlRateConfig->rcExpo8 * (tmpf * tmpf - 25.0f)) * tmpf * (float)(controlRateConfig->rcRate8) / 2500.0f ); } -int16_t rcLookupYaw(int32_t tmp) +int16_t rcLookupYaw(int32_t tmp, controlRateConfig_t *controlRateConfig) { - const int32_t tmp2 = tmp / 20; - return lookupYawRC[tmp2] + (tmp - tmp2 * 20) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 20; + float tmpf = tmp / 100.0f; + return (int16_t)((2500.0f + (float)controlRateConfig->rcYawExpo8* (tmpf * tmpf - 25.0f)) * tmpf / 25.0f ); } int16_t rcLookupThrottle(int32_t tmp) diff --git a/src/main/io/rc_curves.h b/src/main/io/rc_curves.h index 4134f0a319..428dbdc5ca 100644 --- a/src/main/io/rc_curves.h +++ b/src/main/io/rc_curves.h @@ -17,11 +17,9 @@ #pragma once -void generatePitchRollCurve(controlRateConfig_t *controlRateConfig); -void generateYawCurve(controlRateConfig_t *controlRateConfig); void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig); -int16_t rcLookupPitchRoll(int32_t tmp); -int16_t rcLookupYaw(int32_t tmp); +int16_t rcLookupPitchRoll(int32_t tmp, controlRateConfig_t *controlRateConfig); +int16_t rcLookupYaw(int32_t tmp, controlRateConfig_t *controlRateConfig); int16_t rcLookupThrottle(int32_t tmp); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 7cc6ae32f6..05aefaa7ac 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -704,9 +704,6 @@ const clivalue_t valueTable[] = { { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } }, { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} }, { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} }, - { "super_expo_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactor, .config.minmax = {1, 100 } }, - { "super_expo_factor_yaw", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactorYaw, .config.minmax = {1, 100 } }, - { "super_expo_yaw", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.superExpoYawMode, .config.lookup = { TABLE_SUPEREXPO_YAW } }, { "airmode_activate_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.airModeActivateThreshold, .config.minmax = {1000, 2000 } }, { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } }, diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index f932fdb80a..8133aac4ed 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -216,7 +216,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { BOXBLACKBOX, "BLACKBOX;", 26 }, { BOXFAILSAFE, "FAILSAFE;", 27 }, { BOXAIRMODE, "AIR MODE;", 28 }, - { BOXSUPEREXPO, "SUPER EXPO;", 29 }, + //{ BOXSUPEREXPO, "SUPER EXPO;", 29 }, { BOX3DDISABLESWITCH, "DISABLE 3D SWITCH;", 30}, { CHECKBOX_ITEM_COUNT, NULL, 0xFF } }; @@ -544,7 +544,6 @@ void mspInit(serialConfig_t *serialConfig) } if (!feature(FEATURE_AIRMODE)) activeBoxIds[activeBoxIdCount++] = BOXAIRMODE; - if (!feature(FEATURE_SUPEREXPO)) activeBoxIds[activeBoxIdCount++] = BOXSUPEREXPO; activeBoxIds[activeBoxIdCount++] = BOX3DDISABLESWITCH; if (sensors(SENSOR_BARO)) { @@ -650,8 +649,7 @@ static uint32_t packFlightModeFlags(void) IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM | IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX | IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << BOXAIRMODE | - IS_ENABLED(IS_RC_MODE_ACTIVE(BOXSUPEREXPO)) << BOXSUPEREXPO; + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << BOXAIRMODE; for (i = 0; i < activeBoxIdCount; i++) { int flag = (tmp & (1 << activeBoxIds[i])); diff --git a/src/main/mw.c b/src/main/mw.c index c5c5e0af5f..cc515485b4 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -244,14 +244,14 @@ static void updateRcCommands(void) } else { tmp = 0; } - rcCommand[axis] = rcLookupPitchRoll(tmp); + rcCommand[axis] = rcLookupPitchRoll(tmp, currentControlRateProfile); } else if (axis == YAW) { if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { tmp -= masterConfig.rcControlsConfig.yaw_deadband; } else { tmp = 0; } - rcCommand[axis] = rcLookupYaw(tmp) * -masterConfig.yaw_control_direction; + rcCommand[axis] = rcLookupYaw(tmp, currentControlRateProfile) * -masterConfig.yaw_control_direction; } if (rcData[axis] < masterConfig.rxConfig.midrc) { rcCommand[axis] = -rcCommand[axis]; diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index b6e1cfea30..b76873fb15 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -124,9 +124,6 @@ typedef struct rxConfig_s { uint8_t rcSmoothing; uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands uint8_t max_aux_channel; - uint8_t superExpoFactor; // Super Expo Factor - uint8_t superExpoFactorYaw; // Super Expo Factor Yaw - uint8_t superExpoYawMode; // Seperate Super expo for yaw uint16_t airModeActivateThreshold; // Throttle setpoint where airmode gets activated uint16_t rx_min_usec; From 2188ee4be2d5cef471e6e09c5d0d29f43fc4ce1c Mon Sep 17 00:00:00 2001 From: Gary Keeble Date: Wed, 1 Jun 2016 13:50:18 +0100 Subject: [PATCH 71/85] Updated Blackbox 'case' numbers Case numbers need to be consecutive for the header. --- src/main/blackbox/blackbox.c | 66 ++++++++++++++++++------------------ 1 file changed, 33 insertions(+), 33 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index bf43dcc35f..ebda24dca2 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1195,142 +1195,142 @@ static bool blackboxWriteSysinfo() case 18: blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); break; - case 21: + case 19: blackboxPrintfHeaderLine("rates:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); break; - case 22: + case 20: blackboxPrintfHeaderLine("looptime:%d", targetLooptime); break; - case 23: + case 21: blackboxPrintfHeaderLine("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); break; - case 24: + case 22: blackboxPrintfHeaderLine("rollPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); break; - case 25: + case 23: blackboxPrintfHeaderLine("pitchPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); break; - case 26: + case 24: blackboxPrintfHeaderLine("yawPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); break; - case 27: + case 25: blackboxPrintfHeaderLine("altPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); break; - case 28: + case 26: blackboxPrintfHeaderLine("posPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); break; - case 29: + case 27: blackboxPrintfHeaderLine("posrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); break; - case 30: + case 28: blackboxPrintfHeaderLine("navrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); break; - case 31: + case 29: blackboxPrintfHeaderLine("levelPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); break; - case 32: + case 30: blackboxPrintfHeaderLine("magPID:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); break; - case 33: + case 31: blackboxPrintfHeaderLine("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); break; - case 34: + case 32: blackboxPrintfHeaderLine("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); break; - case 35: + case 33: blackboxPrintfHeaderLine("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); break; - case 36: + case 34: blackboxPrintfHeaderLine("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); break; - case 37: + case 35: blackboxPrintfHeaderLine("dynamic_pid:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); break; - case 38: + case 36: blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); break; - case 39: + case 37: blackboxPrintfHeaderLine("yawItermResetRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); break; - case 40: + case 38: blackboxPrintfHeaderLine("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); break; - case 41: + case 39: blackboxPrintfHeaderLine("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold); break; - case 42: + case 40: blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); break; - case 43: + case 41: blackboxPrintfHeaderLine("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); break; - case 44: + case 42: blackboxPrintfHeaderLine("gyro_lpf:%d", masterConfig.gyro_lpf); break; - case 45: + case 43: blackboxPrintfHeaderLine("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); break; - case 46: + case 44: blackboxPrintfHeaderLine("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); break; - case 47: + case 45: blackboxPrintfHeaderLine("acc_hardware:%d", masterConfig.acc_hardware); break; - case 48: + case 46: blackboxPrintfHeaderLine("baro_hardware:%d", masterConfig.baro_hardware); break; - case 49: + case 47: blackboxPrintfHeaderLine("mag_hardware:%d", masterConfig.mag_hardware); break; - case 50: + case 48: blackboxPrintfHeaderLine("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); break; - case 51: + case 49: blackboxPrintfHeaderLine("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); break; - case 52: + case 50: blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); break; - case 53: + case 51: blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures); break; default: From 090c05b7b8194e050bb72e162edd6b7bb6c5af1c Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 1 Jun 2016 18:21:05 +0200 Subject: [PATCH 72/85] Fix Dterm In blackbox --- src/main/flight/pid.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 8dc3f28f1f..45ddc72682 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -231,6 +231,8 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // prevent "yaw jump" during yaw correction axisPID[YAW] = constrain(axisPID[YAW], -yaw_jump_prevention_limit - ABS(rcCommand[YAW]), yaw_jump_prevention_limit + ABS(rcCommand[YAW])); } + + DTerm = 0.0f; // needed for blackbox } else { delta = -(gyroRate - lastRate[axis]); lastRate[axis] = gyroRate; @@ -353,6 +355,8 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // prevent "yaw jump" during yaw correction axisPID[YAW] = constrain(axisPID[YAW], -yaw_jump_prevention_limit - ABS(rcCommand[YAW]), yaw_jump_prevention_limit + ABS(rcCommand[YAW])); } + + DTerm = 0; // needed for blackbox } else { delta = -(gyroRate - lastRate[axis]); lastRate[axis] = gyroRate; From 704c09ccedaf5e644b8c1ca83ee9cc42c6730130 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 1 Jun 2016 18:29:17 +0200 Subject: [PATCH 73/85] Add Additional Anti desync option (Airmode saturation limit) --- src/main/flight/mixer.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index f305ded593..e6d6b00118 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -823,7 +823,7 @@ void mixTable(void) rollPitchYawMix[i] = qMultiply(mixReduction,rollPitchYawMix[i]); } // Get the maximum correction by setting offset to center - throttleMin = throttleMax = throttleMin + (throttleRange / 2); + if (!escAndServoConfig->escDesyncProtection) throttleMin = throttleMax = throttleMin + (throttleRange / 2); if (debugMode == DEBUG_AIRMODE && i < 3) debug[1] = rollPitchYawMixRange; } else { From a3c1f6e168bc4a442023c2383e06c051dc86da7a Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 1 Jun 2016 20:58:00 +0200 Subject: [PATCH 74/85] Add Back Iterm limit for saturation scenarios --- src/main/flight/mixer.c | 14 ++++++++++---- src/main/flight/mixer.h | 2 +- src/main/flight/pid.c | 17 +++++++++++++++-- src/main/io/serial_cli.c | 2 +- 4 files changed, 27 insertions(+), 8 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index e6d6b00118..abf8e27832 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -817,6 +817,7 @@ void mixTable(void) throttleRange = throttleMax - throttleMin; if (rollPitchYawMixRange > throttleRange) { + motorLimitReached = true; mixReduction = qConstruct(throttleRange, rollPitchYawMixRange); for (i = 0; i < motorCount; i++) { @@ -827,6 +828,7 @@ void mixTable(void) if (debugMode == DEBUG_AIRMODE && i < 3) debug[1] = rollPitchYawMixRange; } else { + motorLimitReached = false; throttleMin = throttleMin + (rollPitchYawMixRange / 2); throttleMax = throttleMax - (rollPitchYawMixRange / 2); } @@ -857,11 +859,15 @@ void mixTable(void) // Experimental Code. Anti Desync feature for ESC's if (escAndServoConfig->escDesyncProtection) { - const int16_t maxThrottleStep = escAndServoConfig->escDesyncProtection / (1000 / targetPidLooptime); - static int16_t motorPrevious[MAX_SUPPORTED_MOTORS]; + const int16_t maxThrottleStep = constrain(escAndServoConfig->escDesyncProtection / (1000 / targetPidLooptime), 5, 10000); - motor[i] = constrain(motor[i], motorPrevious[i] - maxThrottleStep, motorPrevious[i] + maxThrottleStep); - motorPrevious[i] = motor[i]; + // Only makes sense when it's within the range + if (maxThrottleStep < throttleRange) { + static int16_t motorPrevious[MAX_SUPPORTED_MOTORS]; + + motor[i] = constrain(motor[i], motorPrevious[i] - maxThrottleStep, motorPrevious[i] + maxThrottleStep); + motorPrevious[i] = motor[i]; + } } } diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 109102f20c..8ebd0fd22a 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -189,7 +189,7 @@ void filterServos(void); extern int16_t motor[MAX_SUPPORTED_MOTORS]; extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; - +bool motorLimitReached; struct escAndServoConfig_s; struct rxConfig_s; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 45ddc72682..cc363bdd3b 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -49,6 +49,7 @@ #include "config/runtime_config.h" extern uint8_t motorCount; +extern bool motorLimitReached; uint32_t targetPidLooptime; int16_t axisPID[3]; @@ -60,9 +61,9 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; // PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction uint8_t PIDweight[3]; -static int32_t errorGyroI[3]; +static int32_t errorGyroI[3], errorGyroILimit[3]; #ifndef SKIP_PID_LUXFLOAT -static float errorGyroIf[3]; +static float errorGyroIf[3], errorGyroIfLimit[3];; #endif static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, @@ -215,6 +216,12 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * kI, -250.0f, 250.0f); + if (motorLimitReached) { + errorGyroIf[axis] = constrainf(errorGyroIf[axis], -errorGyroIfLimit[axis], errorGyroIfLimit[axis]); + } else { + errorGyroIfLimit[axis] = ABS(errorGyroIf[axis]); + } + // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. // I coefficient (I8) moved before integration to make limiting independent from PID settings ITerm = errorGyroIf[axis]; @@ -341,6 +348,12 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // I coefficient (I8) moved before integration to make limiting independent from PID settings errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13); + if (motorLimitReached) { + errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]); + } else { + errorGyroILimit[axis] = ABS(errorGyroI[axis]); + } + ITerm = errorGyroI[axis] >> 13; //-----calculate D-term diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 05aefaa7ac..b71ae0b106 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -574,7 +574,7 @@ const clivalue_t valueTable[] = { { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, - { "anti_desync_power_step", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.escDesyncProtection, .config.minmax = { 0, 2000 } }, + { "anti_desync_power_step", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.escDesyncProtection, .config.minmax = { 0, 10000 } }, { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently From c45475b8af549267e37690fec382952977085ee3 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 1 Jun 2016 22:09:22 +0200 Subject: [PATCH 75/85] Fix broken Level Modes --- src/main/flight/pid.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index cc363bdd3b..68022f682c 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -174,7 +174,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_ // ACRO mode, control is GYRO based, direct sticks control is applied to rate PID AngleRate = calculateRate(axis, controlRateConfig); - if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { + if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) { // calculate error angle and limit the angle to the max inclination #ifdef GPS const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), @@ -299,7 +299,7 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate // -----Get the desired angle rate depending on flight mode AngleRateTmp = (int32_t)calculateRate(axis, controlRateConfig); - if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { + if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) { // calculate error angle and limit the angle to max configured inclination #ifdef GPS const int32_t errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), From bb880e68d30fe5c24e9670b7368328d8710ce67a Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 1 Jun 2016 22:44:56 +0200 Subject: [PATCH 76/85] Cleanup Modes --- src/main/flight/pid.c | 2 +- src/main/io/rc_controls.h | 1 - src/main/io/serial_msp.c | 3 +-- 3 files changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 68022f682c..d0c38f086a 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -63,7 +63,7 @@ uint8_t PIDweight[3]; static int32_t errorGyroI[3], errorGyroILimit[3]; #ifndef SKIP_PID_LUXFLOAT -static float errorGyroIf[3], errorGyroIfLimit[3];; +static float errorGyroIf[3], errorGyroIfLimit[3]; #endif static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRateConfig_t *controlRateConfig, diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h index 0f107e403d..a7e7286e27 100644 --- a/src/main/io/rc_controls.h +++ b/src/main/io/rc_controls.h @@ -49,7 +49,6 @@ typedef enum { BOXBLACKBOX, BOXFAILSAFE, BOXAIRMODE, - BOXSUPEREXPO, BOX3DDISABLESWITCH, CHECKBOX_ITEM_COUNT } boxId_e; diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 8133aac4ed..a827db5d40 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -216,8 +216,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { BOXBLACKBOX, "BLACKBOX;", 26 }, { BOXFAILSAFE, "FAILSAFE;", 27 }, { BOXAIRMODE, "AIR MODE;", 28 }, - //{ BOXSUPEREXPO, "SUPER EXPO;", 29 }, - { BOX3DDISABLESWITCH, "DISABLE 3D SWITCH;", 30}, + { BOX3DDISABLESWITCH, "DISABLE 3D SWITCH;", 29}, { CHECKBOX_ITEM_COUNT, NULL, 0xFF } }; From 77dc19e9d94c5b0e12209a3ef87c5161dd80c54b Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Thu, 2 Jun 2016 10:38:33 +0200 Subject: [PATCH 77/85] Fix Fast PWM synced update for non ONESHOT125 --- src/main/flight/mixer.c | 6 +++--- src/main/flight/mixer.h | 2 +- src/main/mw.c | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index abf8e27832..100aeb62f8 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -633,7 +633,7 @@ void writeServos(void) } #endif -void writeMotors(uint8_t unsyncedPwm) +void writeMotors(uint8_t fastPwmProtocol, uint8_t unsyncedPwm) { uint8_t i; @@ -641,7 +641,7 @@ void writeMotors(uint8_t unsyncedPwm) pwmWriteMotor(i, motor[i]); - if (feature(FEATURE_ONESHOT125) && !unsyncedPwm) { + if (fastPwmProtocol && !unsyncedPwm) { pwmCompleteOneshotMotorUpdate(motorCount); } } @@ -653,7 +653,7 @@ void writeAllMotors(int16_t mc) // Sends commands to all motors for (i = 0; i < motorCount; i++) motor[i] = mc; - writeMotors(1); + writeMotors(1,1); } void stopMotors(void) diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 8ebd0fd22a..8ccd45cb37 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -213,6 +213,6 @@ int servoDirection(int servoIndex, int fromChannel); #endif void mixerResetDisarmedMotors(void); void mixTable(void); -void writeMotors(uint8_t unsyncedPwm); +void writeMotors(uint8_t fastPwmProtocol, uint8_t unsyncedPwm); void stopMotors(void); void StopPwmAllMotors(void); diff --git a/src/main/mw.c b/src/main/mw.c index cc515485b4..f5865a27b4 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -742,7 +742,7 @@ void subTaskMotorUpdate(void) #endif if (motorControlEnable) { - writeMotors(masterConfig.use_unsyncedPwm); + writeMotors(masterConfig.fast_pwm_protocol, masterConfig.use_unsyncedPwm); } if (debugMode == DEBUG_PIDLOOP) {debug[3] = micros() - startTime;} } From 09f5c858175de70ac0b543da9258c0b51380882f Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Thu, 2 Jun 2016 10:41:31 +0200 Subject: [PATCH 78/85] Default Anti Desync --- src/main/config/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 88fd490592..af15469eb1 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -237,7 +237,7 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig) escAndServoConfig->maxthrottle = 1850; escAndServoConfig->mincommand = 1000; escAndServoConfig->servoCenterPulse = 1500; - escAndServoConfig->escDesyncProtection = 0; + escAndServoConfig->escDesyncProtection = 10000; } void resetFlight3DConfig(flight3DConfig_t *flight3DConfig) From 6c8a8614fc89d471070e704b85c3eed5498708bf Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Thu, 2 Jun 2016 11:06:03 +0200 Subject: [PATCH 79/85] Rate limiter --- src/main/flight/pid.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index d0c38f086a..99cc25ae06 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -80,14 +80,14 @@ float calculateRate(int axis, const controlRateConfig_t *controlRateConfig) { if (isSuperExpoActive()) { float rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); - rcFactor = 1.0f / (1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f))); + rcFactor = constrainf(1.0f / (1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f))), 0.01f, 1.00f); angleRate = rcFactor * ((27 * rcCommand[axis]) / 16.0f); } else { angleRate = (float)((controlRateConfig->rates[axis] + 27) * rcCommand[axis]) / 16.0f; } - return angleRate; + return constrainf(angleRate, -8190, 8290); // Rate limit protection } uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) { From a74acccb84172e101fa10e29d983310bb0986c26 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Thu, 2 Jun 2016 17:09:32 +0200 Subject: [PATCH 80/85] Add rc_rate_yaw // SuperExpo feature renamed to SUPEREXPO_RATES --- src/main/config/config.c | 5 +++-- src/main/config/config.h | 2 +- src/main/flight/pid.c | 4 ++-- src/main/io/rc_controls.c | 2 +- src/main/io/rc_controls.h | 1 + src/main/io/rc_curves.c | 10 ++-------- src/main/io/rc_curves.h | 3 +-- src/main/io/serial_cli.c | 3 ++- src/main/mw.c | 4 ++-- 9 files changed, 15 insertions(+), 19 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index af15469eb1..46fcd292a0 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -141,7 +141,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 139; +static const uint8_t EEPROM_CONF_VERSION = 140; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -310,6 +310,7 @@ void resetSerialConfig(serialConfig_t *serialConfig) static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcRate8 = 100; + controlRateConfig->rcYawRate8 = 100; controlRateConfig->rcExpo8 = 10; controlRateConfig->thrMid8 = 50; controlRateConfig->thrExpo8 = 0; @@ -399,7 +400,7 @@ static void resetConf(void) #endif featureSet(FEATURE_FAILSAFE); - featureSet(FEATURE_SUPEREXPO); + featureSet(FEATURE_SUPEREXPO_RATES); // global settings masterConfig.current_profile_index = 0; // default profile diff --git a/src/main/config/config.h b/src/main/config/config.h index 24fe20ea62..7bd7a2e052 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -45,7 +45,7 @@ typedef enum { FEATURE_CHANNEL_FORWARDING = 1 << 20, FEATURE_TRANSPONDER = 1 << 21, FEATURE_AIRMODE = 1 << 22, - FEATURE_SUPEREXPO = 1 << 23, + FEATURE_SUPEREXPO_RATES = 1 << 23, } features_e; void handleOneshotFeatureChangeOnRestart(void); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 99cc25ae06..f9f2a22317 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -80,14 +80,14 @@ float calculateRate(int axis, const controlRateConfig_t *controlRateConfig) { if (isSuperExpoActive()) { float rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); - rcFactor = constrainf(1.0f / (1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f))), 0.01f, 1.00f); + rcFactor = 1.0f / (constrainf(1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f)), 0.01f, 1.00f)); angleRate = rcFactor * ((27 * rcCommand[axis]) / 16.0f); } else { angleRate = (float)((controlRateConfig->rates[axis] + 27) * rcCommand[axis]) / 16.0f; } - return constrainf(angleRate, -8190, 8290); // Rate limit protection + return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection } uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) { diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 4e7344ac9b..0bbcadc09d 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -76,7 +76,7 @@ bool isAirmodeActive(void) { } bool isSuperExpoActive(void) { - return (feature(FEATURE_SUPEREXPO)); + return (feature(FEATURE_SUPEREXPO_RATES)); } void blackboxLogInflightAdjustmentEvent(adjustmentFunction_e adjustmentFunction, int32_t newValue) { diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h index a7e7286e27..a5e96e15c6 100644 --- a/src/main/io/rc_controls.h +++ b/src/main/io/rc_controls.h @@ -136,6 +136,7 @@ typedef struct modeActivationCondition_s { typedef struct controlRateConfig_s { uint8_t rcRate8; + uint8_t rcYawRate8; uint8_t rcExpo8; uint8_t thrMid8; uint8_t thrExpo8; diff --git a/src/main/io/rc_curves.c b/src/main/io/rc_curves.c index 2ed3919747..ee2fe326f0 100644 --- a/src/main/io/rc_curves.c +++ b/src/main/io/rc_curves.c @@ -46,16 +46,10 @@ void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoCo } } -int16_t rcLookupPitchRoll(int32_t tmp, controlRateConfig_t *controlRateConfig) +int16_t rcLookup(int32_t tmp, uint8_t expo, uint8_t rate) { float tmpf = tmp / 100.0f; - return (int16_t)((2500.0f + (float)controlRateConfig->rcExpo8 * (tmpf * tmpf - 25.0f)) * tmpf * (float)(controlRateConfig->rcRate8) / 2500.0f ); -} - -int16_t rcLookupYaw(int32_t tmp, controlRateConfig_t *controlRateConfig) -{ - float tmpf = tmp / 100.0f; - return (int16_t)((2500.0f + (float)controlRateConfig->rcYawExpo8* (tmpf * tmpf - 25.0f)) * tmpf / 25.0f ); + return (int16_t)((2500.0f + (float)expo * (tmpf * tmpf - 25.0f)) * tmpf * (float)(rate) / 2500.0f ); } int16_t rcLookupThrottle(int32_t tmp) diff --git a/src/main/io/rc_curves.h b/src/main/io/rc_curves.h index 428dbdc5ca..747a934df3 100644 --- a/src/main/io/rc_curves.h +++ b/src/main/io/rc_curves.h @@ -19,7 +19,6 @@ void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig); -int16_t rcLookupPitchRoll(int32_t tmp, controlRateConfig_t *controlRateConfig); -int16_t rcLookupYaw(int32_t tmp, controlRateConfig_t *controlRateConfig); +int16_t rcLookup(int32_t tmp, uint8_t expo, uint8_t rate); int16_t rcLookupThrottle(int32_t tmp); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index b71ae0b106..d077b96148 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -199,7 +199,7 @@ static const char * const featureNames[] = { "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", - "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO", + "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES", NULL }; @@ -695,6 +695,7 @@ const clivalue_t valueTable[] = { #endif { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } }, + { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawRate8, .config.minmax = { 0, 250 } }, { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } }, { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } }, { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } }, diff --git a/src/main/mw.c b/src/main/mw.c index f5865a27b4..771de46e2c 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -244,14 +244,14 @@ static void updateRcCommands(void) } else { tmp = 0; } - rcCommand[axis] = rcLookupPitchRoll(tmp, currentControlRateProfile); + rcCommand[axis] = rcLookup(tmp, currentControlRateProfile->rcExpo8, currentControlRateProfile->rcRate8); } else if (axis == YAW) { if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { tmp -= masterConfig.rcControlsConfig.yaw_deadband; } else { tmp = 0; } - rcCommand[axis] = rcLookupYaw(tmp, currentControlRateProfile) * -masterConfig.yaw_control_direction; + rcCommand[axis] = rcLookup(tmp, currentControlRateProfile->rcYawExpo8, currentControlRateProfile->rcYawRate8) * -masterConfig.yaw_control_direction;; } if (rcData[axis] < masterConfig.rxConfig.midrc) { rcCommand[axis] = -rcCommand[axis]; From db5184d6034a84401d49fa8decd6a4c94bd73777 Mon Sep 17 00:00:00 2001 From: Gary Keeble Date: Fri, 3 Jun 2016 15:18:54 +0100 Subject: [PATCH 81/85] Add rcYawRate into Blackbox header and Calculate Rate Function Add the new Yaw Rate parameter into the log header --- src/main/blackbox/blackbox.c | 77 +++++++++++++++++++----------------- src/main/flight/pid.c | 2 +- 2 files changed, 41 insertions(+), 38 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index ebda24dca2..40fa2e2306 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1181,156 +1181,159 @@ static bool blackboxWriteSysinfo() blackboxPrintfHeaderLine("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); break; case 14: - blackboxPrintfHeaderLine("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8); + blackboxPrintfHeaderLine("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); break; case 15: - blackboxPrintfHeaderLine("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8); + blackboxPrintfHeaderLine("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8); break; case 16: - blackboxPrintfHeaderLine("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8); + blackboxPrintfHeaderLine("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8); break; case 17: - blackboxPrintfHeaderLine("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID); + blackboxPrintfHeaderLine("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8); break; case 18: - blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); + blackboxPrintfHeaderLine("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID); break; case 19: + blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); + break; + case 20: blackboxPrintfHeaderLine("rates:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); break; - case 20: + case 21: blackboxPrintfHeaderLine("looptime:%d", targetLooptime); break; - case 21: + case 22: blackboxPrintfHeaderLine("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); break; - case 22: + case 23: blackboxPrintfHeaderLine("rollPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); break; - case 23: + case 24: blackboxPrintfHeaderLine("pitchPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); break; - case 24: + case 25: blackboxPrintfHeaderLine("yawPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); break; - case 25: + case 26: blackboxPrintfHeaderLine("altPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); break; - case 26: + case 27: blackboxPrintfHeaderLine("posPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); break; - case 27: + case 28: blackboxPrintfHeaderLine("posrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); break; - case 28: + case 29: blackboxPrintfHeaderLine("navrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); break; - case 29: + case 30: blackboxPrintfHeaderLine("levelPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); break; - case 30: + case 31: blackboxPrintfHeaderLine("magPID:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); break; - case 31: + case 32: blackboxPrintfHeaderLine("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); break; - case 32: + case 33: blackboxPrintfHeaderLine("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); break; - case 33: + case 34: blackboxPrintfHeaderLine("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); break; - case 34: + case 35: blackboxPrintfHeaderLine("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); break; - case 35: + case 36: blackboxPrintfHeaderLine("dynamic_pid:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); break; - case 36: + case 37: blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); break; - case 37: + case 38: blackboxPrintfHeaderLine("yawItermResetRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); break; - case 38: + case 39: blackboxPrintfHeaderLine("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); break; - case 39: + case 40: blackboxPrintfHeaderLine("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold); break; - case 40: + case 41: blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); break; - case 41: + case 42: blackboxPrintfHeaderLine("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); break; - case 42: + case 43: blackboxPrintfHeaderLine("gyro_lpf:%d", masterConfig.gyro_lpf); break; - case 43: + case 44: blackboxPrintfHeaderLine("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); break; - case 44: + case 45: blackboxPrintfHeaderLine("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); break; - case 45: + case 46: blackboxPrintfHeaderLine("acc_hardware:%d", masterConfig.acc_hardware); break; - case 46: + case 47: blackboxPrintfHeaderLine("baro_hardware:%d", masterConfig.baro_hardware); break; - case 47: + case 48: blackboxPrintfHeaderLine("mag_hardware:%d", masterConfig.mag_hardware); break; - case 48: + case 49: blackboxPrintfHeaderLine("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); break; - case 49: + case 50: blackboxPrintfHeaderLine("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); break; - case 50: + case 51: blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); break; - case 51: + case 52: blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures); break; default: diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index f9f2a22317..b9d706dd7d 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -79,7 +79,7 @@ float calculateRate(int axis, const controlRateConfig_t *controlRateConfig) { float angleRate; if (isSuperExpoActive()) { - float rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); + float rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcYawRate8 / 100.0f))) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f))); rcFactor = 1.0f / (constrainf(1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f)), 0.01f, 1.00f)); angleRate = rcFactor * ((27 * rcCommand[axis]) / 16.0f); From 1e68552a0c7365c80f28402f8e6f7376f7619251 Mon Sep 17 00:00:00 2001 From: kc10kevin Date: Sun, 5 Jun 2016 05:53:27 -0500 Subject: [PATCH 82/85] Initial FURYF3 Target --- Makefile | 37 ++- fake_travis_build.sh | 3 +- src/main/config/config.c | 9 +- src/main/drivers/bus_i2c_stm32f30x.c | 2 + src/main/drivers/pwm_mapping.c | 48 +++ src/main/drivers/system.c | 2 +- src/main/drivers/timer.c | 23 ++ src/main/io/serial_msp.c | 2 +- src/main/main.c | 5 + src/main/sensors/initialisation.c | 13 + src/main/sensors/sonar.c | 2 +- src/main/target/FURYF3/system_stm32f30x.c | 371 ++++++++++++++++++++++ src/main/target/FURYF3/system_stm32f30x.h | 76 +++++ src/main/target/FURYF3/target.h | 221 +++++++++++++ top_makefile | 2 + 15 files changed, 808 insertions(+), 8 deletions(-) create mode 100644 src/main/target/FURYF3/system_stm32f30x.c create mode 100644 src/main/target/FURYF3/system_stm32f30x.h create mode 100644 src/main/target/FURYF3/target.h diff --git a/Makefile b/Makefile index e5a4916594..fe5283d572 100644 --- a/Makefile +++ b/Makefile @@ -46,7 +46,7 @@ FORKNAME = betaflight CC3D_TARGETS = CC3D CC3D_OPBL -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3 # Valid targets for OP VCP support VCP_VALID_TARGETS = $(CC3D_TARGETS) @@ -56,9 +56,9 @@ OPBL_VALID_TARGETS = CC3D_OPBL 64K_TARGETS = CJMCU 128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI -256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3 -F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3 # note that there is no hardfault debugging startup file assembly handler for other platforms ifeq ($(DEBUG_HARDFAULTS),F3) @@ -150,6 +150,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ VPATH := $(VPATH):$(FATFS_DIR) endif +ifeq ($(TARGET),FURY) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) \ + +VPATH := $(VPATH):$(FATFS_DIR) +endif + LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion @@ -810,6 +817,30 @@ SINGULARITY_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) +FURYF3_SRC = \ + $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/display_ug2864hsweg01.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_usb_vcp.c \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + drivers/flash_m25p16.c \ + drivers/sonar_hcsr04.c \ + drivers/serial_softserial.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c \ + io/flashfs.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) + # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 7749d64354..4babddd212 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -17,7 +17,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=ALIENFLIGHTF1" \ "TARGET=ALIENFLIGHTF3" \ "TARGET=DOGE" \ - "TARGET=SINGULARITY") + "TARGET=SINGULARITY" \ + "TARGET=FURYF3") #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/src/main/config/config.c b/src/main/config/config.c index 46fcd292a0..6f0b952755 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -385,7 +385,7 @@ static void resetConf(void) masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerMode = MIXER_QUADX; featureClearAll(); -#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY) +#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY) || defined(FURYF3) featureSet(FEATURE_RX_PPM); #endif @@ -596,6 +596,13 @@ static void resetConf(void) masterConfig.blackbox_rate_denom = 1; #endif +#if defined(FURYF3) + featureSet(FEATURE_BLACKBOX); + masterConfig.blackbox_device = 2; + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; +#endif + // alternative defaults settings for COLIBRI RACE targets #if defined(COLIBRI_RACE) masterConfig.escAndServoConfig.minthrottle = 1025; diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 8b33e7e461..b45f6bd6bb 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -30,6 +30,7 @@ #ifndef SOFT_I2C +#if !defined(I2C1_SCL_GPIO) #define I2C1_SCL_GPIO GPIOB #define I2C1_SCL_GPIO_AF GPIO_AF_4 #define I2C1_SCL_PIN GPIO_Pin_6 @@ -40,6 +41,7 @@ #define I2C1_SDA_PIN GPIO_Pin_7 #define I2C1_SDA_PIN_SOURCE GPIO_PinSource7 #define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB +#endif #if !defined(I2C2_SCL_GPIO) #define I2C2_SCL_GPIO GPIOF diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index b786ba0cee..d6b523f8c8 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -748,6 +748,54 @@ static const uint16_t airPWM[] = { }; #endif +#ifdef FURYF3 +static const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM2 | (MAP_TO_SERVO_OUTPUT << 8), + PWM3 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +static const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; +#endif + static const uint16_t * const hardwareMaps[] = { multiPWM, multiPPM, diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 1cc192121f..af25ef0c99 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -83,7 +83,7 @@ void EXTI15_10_IRQHandler(void) extiHandler(EXTI15_10_IRQn); } -#if defined(CC3D) +#if defined(CC3D) || defined(FURYF3) void EXTI3_IRQHandler(void) { extiHandler(EXTI3_IRQn); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index bc52c6e3cc..659236602a 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -416,6 +416,29 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { #endif +#ifdef FURYF3 +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, GPIOB, Pin_3, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1}, // PPM IN + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM4 - S1 + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM5 - S2 + { TIM17, GPIOB, Pin_5, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_10}, // PWM6 - S3 + { TIM16, GPIOB, Pin_4, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_1}, // PWM7 - S4 + + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO TIMER - LED_STRIP + +}; + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17)) + +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) +#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) + +#endif + #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS) #define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4 diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index a827db5d40..dcae1a0ef1 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -125,7 +125,7 @@ void setGyroSamplingSpeed(uint16_t looptime) { masterConfig.mag_hardware = 1; masterConfig.pid_process_denom = 2; } else if (looptime < 375) { -#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO) || defined(DOGE) +#if defined(LUX_RACE) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(ALIENFLIGHTF3) || defined(SPRACINGF3EVO) || defined(DOGE) || defined(FURYF3) masterConfig.acc_hardware = 0; #else masterConfig.acc_hardware = 1; diff --git a/src/main/main.c b/src/main/main.c index d89bb44923..e05eefb0ca 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -426,6 +426,11 @@ void init(void) } #endif +#if defined(FURYF3) && defined(SONAR) && defined(USE_SOFTSERIAL1) + if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { + serialRemovePort(SERIAL_PORT_SOFTSERIAL1); + } +#endif #ifdef USE_I2C #if defined(NAZE) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index ab9b27c898..a27ca0663d 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -223,6 +223,19 @@ const extiConfig_t *selectMPUIntExtiConfig(void) } #endif +#if defined(FURYF3) + static const extiConfig_t FURYF3MPUIntExtiConfig = { + .gpioAHBPeripherals = RCC_AHBPeriph_GPIOA, + .gpioPort = GPIOA, + .gpioPin = Pin_3, + .exti_port_source = EXTI_PortSourceGPIOA, + .exti_pin_source = EXTI_PinSource3, + .exti_line = EXTI_Line3, + .exti_irqn = EXTI3_IRQn + }; + return &FURYF3MPUIntExtiConfig; +#endif + return NULL; } diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 4e0b2bea52..93104d0cd7 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -101,7 +101,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon .exti_irqn = EXTI0_IRQn }; return &sonarHardware; -#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) +#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) UNUSED(batteryConfig); static const sonarHardware_t const sonarHardware = { .trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) diff --git a/src/main/target/FURYF3/system_stm32f30x.c b/src/main/target/FURYF3/system_stm32f30x.c new file mode 100644 index 0000000000..de8a873131 --- /dev/null +++ b/src/main/target/FURYF3/system_stm32f30x.c @@ -0,0 +1,371 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.c + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F30x devices, + * and is generated by the clock configuration tool + * stm32f30x_Clock_Configuration_V1.0.0.xls + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f30x.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f30x.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and HSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define + * in "stm32f30x.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + * Supported STM32F30x device + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 72000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *---------------------------------------------------------------------------- + * PLLMUL | 9 + *----------------------------------------------------------------------------- + * PREDIV | 1 + *----------------------------------------------------------------------------- + * USB Clock | ENABLE + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 2 + *----------------------------------------------------------------------------- + * Prefetch Buffer | ON + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f30x_system + * @{ + */ + +/** @addtogroup STM32F30x_System_Private_Includes + * @{ + */ + +#include "stm32f30x.h" + +uint32_t hse_value = HSE_VALUE; + +/** + * @} + */ + +/* Private typedef -----------------------------------------------------------*/ + +/** @addtogroup STM32F30x_System_Private_Defines + * @{ + */ +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ + +/** @addtogroup STM32F30x_System_Private_Variables + * @{ + */ + + uint32_t SystemCoreClock = 72000000; + + __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +/** + * @} + */ + +/** @addtogroup STM32F30x_System_Private_FunctionPrototypes + * @{ + */ + +void SetSysClock(void); + +/** + * @} + */ + +/** @addtogroup STM32F30x_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemFrequency variable. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* FPU settings ------------------------------------------------------------*/ + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ + #endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR &= 0xF87FC00C; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + + /* Reset PREDIV1[3:0] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFFFF0; + + /* Reset USARTSW[1:0], I2CSW and TIMs bits */ + RCC->CFGR3 &= (uint32_t)0xFF00FCCC; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + + /* Configure the System clock source, PLL Multiplier and Divider factors, + AHB/APBx prescalers and Flash settings ----------------------------------*/ + //SetSysClock(); // called from main() + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + { + prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + } + break; + default: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ +void SetSysClock(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer and set Flash Latency */ + FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1; + + /* HCLK = SYSCLK / 1 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK / 1 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK / 2 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + + /* PLL configuration */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9); + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/main/target/FURYF3/system_stm32f30x.h b/src/main/target/FURYF3/system_stm32f30x.h new file mode 100644 index 0000000000..57e5e05d74 --- /dev/null +++ b/src/main/target/FURYF3/system_stm32f30x.h @@ -0,0 +1,76 @@ +/** + ****************************************************************************** + * @file system_stm32f30x.h + * @author MCD Application Team + * @version V1.1.1 + * @date 28-March-2014 + * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2014 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f30x_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F30X_H +#define __SYSTEM_STM32F30X_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/** @addtogroup STM32F30x_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F30X_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h new file mode 100644 index 0000000000..0fbe17c57b --- /dev/null +++ b/src/main/target/FURYF3/target.h @@ -0,0 +1,221 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "FURY" + +#define LED0 + +#define LED0_GPIO GPIOC +#define LED0_PIN Pin_14 +#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOC + +#define BEEPER +#define BEEP_GPIO GPIOC +#define BEEP_PIN Pin_15 +#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC +#define BEEPER_INVERTED + +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define GYRO +#define ACC + +#define MPU6000_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA +#define MPU6000_CS_GPIO GPIOA +#define MPU6000_CS_PIN GPIO_Pin_4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA +#define MPU6500_CS_GPIO GPIOA +#define MPU6500_CS_PIN GPIO_Pin_4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG // changedkb 270 +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG // changedkb 270 + +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW90_DEG // changedkb 270 +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW90_DEG // changedkb 270 + +#define BARO +#define USE_BARO_MS5611 +#define USE_BARO_BMP280 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define SPI2_GPIO GPIOB +#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI2_NSS_PIN Pin_12 +#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 +#define SPI2_SCK_PIN Pin_13 +#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 +#define SPI2_MISO_PIN Pin_14 +#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 +#define SPI2_MOSI_PIN Pin_15 +#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 + +//#define USE_FLASHFS +//#define USE_FLASH_M25P16 +//#define M25P16_CS_GPIO GPIOB +//#define M25P16_CS_PIN GPIO_Pin_12 +//#define M25P16_SPI_INSTANCE SPI2 + +#define USE_SDCARD +#define USE_SDCARD_SPI2 + +#define SDCARD_DETECT_INVERTED + +#define SDCARD_DETECT_PIN GPIO_Pin_2 +#define SDCARD_DETECT_EXTI_LINE EXTI_Line2 +#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2 +#define SDCARD_DETECT_GPIO_PORT GPIOB +#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOB +#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB +#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn + +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_GPIO SPI2_GPIO +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN + +// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128 +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 + +// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 + +// Performance logging for SD card operations: +// #define AFATFS_USE_INTROSPECTIVE_LOGGING + +#define USABLE_TIMER_CHANNEL_COUNT 8 + +#define USB_IO + +#define USE_VCP +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define USE_SOFTSERIAL1 +#define SERIAL_PORT_COUNT 5 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_14 // PA14 +#define UART2_RX_PIN GPIO_Pin_15 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource14 +#define UART2_RX_PINSOURCE GPIO_PinSource15 + +#ifndef UART3_GPIO +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 +#endif + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 1 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 2 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4) + +#define I2C1_SCL_GPIO GPIOB +#define I2C1_SCL_GPIO_AF GPIO_AF_4 +#define I2C1_SCL_PIN GPIO_Pin_8 +#define I2C1_SCL_PIN_SOURCE GPIO_PinSource8 +#define I2C1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB +#define I2C1_SDA_GPIO GPIOB +#define I2C1_SDA_GPIO_AF GPIO_AF_4 +#define I2C1_SDA_PIN GPIO_Pin_9 +#define I2C1_SDA_PIN_SOURCE GPIO_PinSource9 +#define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC1 +#define ADC_DMA_CHANNEL DMA1_Channel1 +#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 + +#define VBAT_ADC_GPIO GPIOA +#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 +#define VBAT_ADC_CHANNEL ADC_Channel_1 + +#define RSSI_ADC_GPIO GPIOA +#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 +#define RSSI_ADC_CHANNEL ADC_Channel_2 + +#define CURRENT_METER_ADC_GPIO GPIOA +#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2 +#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3 + +#define LED_STRIP +#define LED_STRIP_TIMER TIM1 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_6 +#define WS2811_PIN GPIO_Pin_8 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM1 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define BLACKBOX +#define DISPLAY +#define GPS +#define SERIAL_RX +#define TELEMETRY +#define USE_SERVOS +#define USE_CLI +#define SONAR + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PORT GPIOB +#define BIND_PIN Pin_11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE \ No newline at end of file diff --git a/top_makefile b/top_makefile index 4b1bb90e78..bbc1f43f14 100644 --- a/top_makefile +++ b/top_makefile @@ -15,6 +15,7 @@ ALL_TARGETS += ircfusionf3 ALL_TARGETS += afromini ALL_TARGETS += doge ALL_TARGETS += singularity +ALL_TARGETS += furyf3 CLEAN_TARGETS := $(addprefix clean_, $(ALL_TARGETS)) @@ -35,6 +36,7 @@ clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3 clean_afromini afromini : opts := TARGET=AFROMINI clean_doge doge : opts := TARGET=DOGE clean_singularity singularity : opts := TARGET=SINGULARITY +clean_furyf3 furyf3 : opts := TARGET=FURYF3 .PHONY: all clean From 047d962e6588e14f71470e0d6596b7c5360b7dc3 Mon Sep 17 00:00:00 2001 From: Gary Keeble Date: Mon, 6 Jun 2016 18:22:52 +0100 Subject: [PATCH 83/85] Blackbox Coding Simplification Simplified header record writing using macros to outnumber the case statements --- src/main/blackbox/blackbox.c | 288 +++++++++++------------------------ 1 file changed, 91 insertions(+), 197 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 40fa2e2306..80df3ba141 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1118,6 +1118,15 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v return xmitState.headerIndex < headerCount; } +#ifndef BLACKBOX_PRINT_HEADER_LINE +#define BLACKBOX_PRINT_HEADER_LINE(x, ...) case __COUNTER__: \ + blackboxPrintfHeaderLine(x, __VA_ARGS__); \ + break; +#define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) case __COUNTER__: \ + {__VA_ARGS__}; \ + break; +#endif + /** * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns * true iff transmission is complete, otherwise call again later to continue transmission. @@ -1130,212 +1139,97 @@ static bool blackboxWriteSysinfo() } switch (xmitState.headerIndex) { - case 0: - blackboxPrintfHeaderLine("Firmware type:Cleanflight"); - break; - case 1: - blackboxPrintfHeaderLine("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName); - break; - case 2: - blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime); - break; - case 3: - blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); - break; - case 4: - blackboxPrintfHeaderLine("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8); - break; - case 5: - blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); - break; - case 6: - blackboxPrintfHeaderLine("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle); - break; - case 7: - blackboxPrintfHeaderLine("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale)); - break; - case 8: - blackboxPrintfHeaderLine("acc_1G:%u", acc_1G); - break; - case 9: + BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight"); + BLACKBOX_PRINT_HEADER_LINE("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName); + BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime); + BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); + BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale)); + BLACKBOX_PRINT_HEADER_LINE("acc_1G:%u", acc_1G); + + BLACKBOX_PRINT_HEADER_LINE_CUSTOM( if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { blackboxPrintfHeaderLine("vbatscale:%u", masterConfig.batteryConfig.vbatscale); } else { xmitState.headerIndex += 2; // Skip the next two vbat fields too } - break; - case 10: - blackboxPrintfHeaderLine("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage, - masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage); - break; - case 11: - blackboxPrintfHeaderLine("vbatref:%u", vbatReference); - break; - case 12: + ); + + BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage, + masterConfig.batteryConfig.vbatwarningcellvoltage, + masterConfig.batteryConfig.vbatmaxcellvoltage); + BLACKBOX_PRINT_HEADER_LINE("vbatref:%u", vbatReference); + + BLACKBOX_PRINT_HEADER_LINE_CUSTOM( //Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too: if (feature(FEATURE_CURRENT_METER)) { blackboxPrintfHeaderLine("currentMeter:%d,%d", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale); } - break; - case 13: - blackboxPrintfHeaderLine("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); - break; - case 14: - blackboxPrintfHeaderLine("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); - break; - case 15: - blackboxPrintfHeaderLine("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8); - break; - case 16: - blackboxPrintfHeaderLine("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8); - break; - case 17: - blackboxPrintfHeaderLine("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8); - break; - case 18: - blackboxPrintfHeaderLine("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID); - break; - case 19: - blackboxPrintfHeaderLine("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); - break; - case 20: - blackboxPrintfHeaderLine("rates:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], - masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], - masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); - break; - case 21: - blackboxPrintfHeaderLine("looptime:%d", targetLooptime); - break; - case 22: - blackboxPrintfHeaderLine("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); - break; - case 23: - blackboxPrintfHeaderLine("rollPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); - break; - case 24: - blackboxPrintfHeaderLine("pitchPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); - break; - case 25: - blackboxPrintfHeaderLine("yawPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); - break; - case 26: - blackboxPrintfHeaderLine("altPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); - break; - case 27: - blackboxPrintfHeaderLine("posPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); - break; - case 28: - blackboxPrintfHeaderLine("posrPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); - break; - case 29: - blackboxPrintfHeaderLine("navrPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); - break; - case 30: - blackboxPrintfHeaderLine("levelPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); - break; - case 31: - blackboxPrintfHeaderLine("magPID:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); - break; - case 32: - blackboxPrintfHeaderLine("velPID:%d,%d,%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], - masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); - break; - case 33: - blackboxPrintfHeaderLine("yaw_p_limit:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); - break; - case 34: - blackboxPrintfHeaderLine("yaw_lpf_hz:%d", - (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); - break; - case 35: - blackboxPrintfHeaderLine("dterm_average_count:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); - break; - case 36: - blackboxPrintfHeaderLine("dynamic_pid:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); - break; - case 37: - blackboxPrintfHeaderLine("rollPitchItermResetRate:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); - break; - case 38: - blackboxPrintfHeaderLine("yawItermResetRate:%d", - masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); - break; - case 39: - blackboxPrintfHeaderLine("dterm_lpf_hz:%d", - (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); - break; - case 40: - blackboxPrintfHeaderLine("airmode_activate_throttle:%d", - masterConfig.rxConfig.airModeActivateThreshold); - break; - case 41: - blackboxPrintfHeaderLine("deadband:%d", masterConfig.rcControlsConfig.deadband); - break; - case 42: - blackboxPrintfHeaderLine("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); - break; - case 43: - blackboxPrintfHeaderLine("gyro_lpf:%d", masterConfig.gyro_lpf); - break; - case 44: - blackboxPrintfHeaderLine("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); - break; - case 45: - blackboxPrintfHeaderLine("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); - break; - case 46: - blackboxPrintfHeaderLine("acc_hardware:%d", masterConfig.acc_hardware); - break; - case 47: - blackboxPrintfHeaderLine("baro_hardware:%d", masterConfig.baro_hardware); - break; - case 48: - blackboxPrintfHeaderLine("mag_hardware:%d", masterConfig.mag_hardware); - break; - case 49: - blackboxPrintfHeaderLine("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); - break; - case 50: - blackboxPrintfHeaderLine("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); - break; - case 51: - blackboxPrintfHeaderLine("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); - break; - case 52: - blackboxPrintfHeaderLine("features:%d", masterConfig.enabledFeatures); - break; + ); + + BLACKBOX_PRINT_HEADER_LINE("looptime:%d", targetLooptime); + BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8); + BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); + BLACKBOX_PRINT_HEADER_LINE("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); + BLACKBOX_PRINT_HEADER_LINE("rcYawExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawExpo8); + BLACKBOX_PRINT_HEADER_LINE("thrMid:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrMid8); + BLACKBOX_PRINT_HEADER_LINE("thrExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].thrExpo8); + BLACKBOX_PRINT_HEADER_LINE("dynThrPID:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].dynThrPID); + BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].tpa_breakpoint); + BLACKBOX_PRINT_HEADER_LINE("rates:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[ROLL], + masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[PITCH], + masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rates[YAW]); + BLACKBOX_PRINT_HEADER_LINE("pidController:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.pidController); + BLACKBOX_PRINT_HEADER_LINE("rollPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[ROLL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[ROLL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[ROLL]); + BLACKBOX_PRINT_HEADER_LINE("pitchPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PITCH], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PITCH], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PITCH]); + BLACKBOX_PRINT_HEADER_LINE("yawPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[YAW], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[YAW], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[YAW]); + BLACKBOX_PRINT_HEADER_LINE("altPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDALT], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDALT], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDALT]); + BLACKBOX_PRINT_HEADER_LINE("posPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOS], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOS], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOS]); + BLACKBOX_PRINT_HEADER_LINE("posrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDPOSR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDPOSR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDPOSR]); + BLACKBOX_PRINT_HEADER_LINE("navrPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDNAVR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDNAVR], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDNAVR]); + BLACKBOX_PRINT_HEADER_LINE("levelPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL]); + BLACKBOX_PRINT_HEADER_LINE("magPID:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDMAG]); + BLACKBOX_PRINT_HEADER_LINE("velPID:%d,%d,%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDVEL], + masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDVEL]); + BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_p_limit); + BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.yaw_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_average_count); + BLACKBOX_PRINT_HEADER_LINE("dynamic_pid:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.dynamic_pid); + BLACKBOX_PRINT_HEADER_LINE("rollPitchItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.rollPitchItermIgnoreRate); + BLACKBOX_PRINT_HEADER_LINE("yawItermIgnoreRate:%d", masterConfig.profile[masterConfig.current_profile_index].pidProfile.yawItermIgnoreRate); + BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.dterm_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("deadband:%d", masterConfig.rcControlsConfig.deadband); + BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); + BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf); + BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware); + BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware); + BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.mag_hardware); + BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", masterConfig.gyro_cal_on_first_arm); + BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", masterConfig.batteryConfig.vbatPidCompensation); + BLACKBOX_PRINT_HEADER_LINE("rc_smoothing:%d", masterConfig.rxConfig.rcSmoothing); + BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold); + BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures); + default: return true; } From 6e228eacf5e53c38e2c69569e9d846a3e2e96a55 Mon Sep 17 00:00:00 2001 From: mikeller Date: Tue, 7 Jun 2016 11:39:37 +1200 Subject: [PATCH 84/85] Fixed rateprofile dump / restore --- src/main/io/serial_cli.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index d077b96148..4cad900d68 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -2051,24 +2051,27 @@ static void cliDump(char *cmdline) if (dumpMask & DUMP_ALL) { uint8_t activeProfile = masterConfig.current_profile_index; - uint8_t currentRateIndex = currentProfile->activeRateProfile; uint8_t profileCount; - uint8_t rateCount; for (profileCount=0; profileCountactiveRateProfile; + uint8_t rateCount; for (rateCount=0; rateCount Date: Tue, 7 Jun 2016 20:16:06 +0100 Subject: [PATCH 85/85] Added default features and default rx that can be set in the target.h file. --- src/main/config/config.c | 35 +++++++------------------ src/main/target/ALIENFLIGHTF3/target.h | 1 + src/main/target/CC3D/target.h | 1 + src/main/target/CJMCU/target.h | 1 + src/main/target/COLIBRI_RACE/target.h | 1 + src/main/target/DOGE/target.h | 1 + src/main/target/FURYF3/target.h | 2 ++ src/main/target/LUX_RACE/target.h | 1 + src/main/target/MOTOLAB/target.h | 1 + src/main/target/SINGULARITY/target.h | 2 ++ src/main/target/SPARKY/target.h | 1 + src/main/target/SPRACINGF3/target.h | 3 +++ src/main/target/SPRACINGF3EVO/target.h | 5 ++-- src/main/target/SPRACINGF3MINI/target.h | 2 +- 14 files changed, 29 insertions(+), 28 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 6f0b952755..46f0f669bb 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -73,6 +73,10 @@ #include "config/config_profile.h" #include "config/config_master.h" +#ifndef DEFAULT_RX_FEATURE +#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM +#endif + #define BRUSHED_MOTORS_PWM_RATE 16000 #define BRUSHLESS_MOTORS_PWM_RATE 400 @@ -382,25 +386,20 @@ static void resetConf(void) memset(&masterConfig, 0, sizeof(master_t)); setProfile(0); - masterConfig.version = EEPROM_CONF_VERSION; - masterConfig.mixerMode = MIXER_QUADX; featureClearAll(); -#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY) || defined(FURYF3) - featureSet(FEATURE_RX_PPM); + featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES); +#ifdef DEFAULT_FEATURES + featureSet(DEFAULT_FEATURES); #endif -//#if defined(SPRACINGF3MINI) -// featureSet(FEATURE_DISPLAY); -//#endif - #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. featureSet(FEATURE_VBAT); #endif - featureSet(FEATURE_FAILSAFE); - featureSet(FEATURE_SUPEREXPO_RATES); + masterConfig.version = EEPROM_CONF_VERSION; + masterConfig.mixerMode = MIXER_QUADX; // global settings masterConfig.current_profile_index = 0; // default profile @@ -574,7 +573,6 @@ static void resetConf(void) #endif #ifdef SPRACINGF3 - featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 1; #ifdef TRANSPONDER static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware @@ -597,7 +595,6 @@ static void resetConf(void) #endif #if defined(FURYF3) - featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 2; masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; @@ -609,16 +606,6 @@ static void resetConf(void) masterConfig.escAndServoConfig.maxthrottle = 1980; masterConfig.batteryConfig.vbatmaxcellvoltage = 45; masterConfig.batteryConfig.vbatmincellvoltage = 30; - - featureSet(FEATURE_VBAT); - featureSet(FEATURE_FAILSAFE); -#endif - -#ifdef SPRACINGF3EVO - featureSet(FEATURE_TRANSPONDER); - featureSet(FEATURE_RSSI_ADC); - featureSet(FEATURE_CURRENT_METER); - featureSet(FEATURE_TELEMETRY); #endif // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets @@ -699,14 +686,12 @@ static void resetConf(void) // alternative defaults settings for SINGULARITY target #if defined(SINGULARITY) - featureSet(FEATURE_BLACKBOX); masterConfig.blackbox_device = 1; masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; masterConfig.batteryConfig.vbatscale = 77; - featureSet(FEATURE_RX_SERIAL); masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; #endif @@ -823,7 +808,7 @@ void activateConfig(void) void validateAndFixConfig(void) { if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) { - featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM + featureSet(FEATURE_RX_PARALLEL_PWM); } if (featureConfigured(FEATURE_RX_PPM)) { diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 79365c62e5..144ba1f7dd 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -157,6 +157,7 @@ //#define DISPLAY #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // USART2, PA3 diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index ca94199b8f..3f6b753b52 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -128,6 +128,7 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SONAR //#define GPS diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index cf32393b42..cd9cb19123 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -60,6 +60,7 @@ #define SERIAL_RX //#define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // USART2, PA3 diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 92edd4fea2..d95a9cc48a 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -192,5 +192,6 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 008557d335..fa18385a83 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -190,6 +190,7 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // Use UART3 for speksat diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 0fbe17c57b..99d7340d79 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -212,6 +212,8 @@ #define USE_SERVOS #define USE_CLI #define SONAR +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define SPEKTRUM_BIND // USART3, diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index a3b370df7a..2d04a2fee6 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -154,6 +154,7 @@ #define TELEMETRY #define SERIAL_RX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 9f168587fd..23e54ab3b8 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -121,6 +121,7 @@ #define TELEMETRY #define BLACKBOX #define SERIAL_RX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM //#define GPS //#define GTUNE #define DISPLAY diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 54d1824444..fbc58bae34 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -127,6 +127,8 @@ #define GPS #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL) #define SPEKTRUM_BIND // USART2, PA15 diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 8ff56c86ca..5e69ef1089 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -126,6 +126,7 @@ #define TELEMETRY #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define LED_STRIP #if 1 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index c5a0e5265d..0e0ede72ce 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -158,6 +158,9 @@ #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX + #define SPEKTRUM_BIND // USART3, #define BIND_PORT GPIOB diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 4586dbc2d1..73ea225dca 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -206,8 +206,6 @@ #define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 #define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM - #define GPS #define BLACKBOX #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT @@ -217,6 +215,9 @@ #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) + #define SPEKTRUM_BIND // USART3, #define BIND_PORT GPIOB diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 5459d4f9a2..6151d35492 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -212,10 +212,10 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define TELEMETRY #define SERIAL_RX -#define AUTOTUNE #define DISPLAY #define USE_SERVOS #define USE_CLI +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define BUTTONS #define BUTTON_A_PORT GPIOB