diff --git a/Makefile b/Makefile index bee0cbcba..1397ce956 100755 --- a/Makefile +++ b/Makefile @@ -38,7 +38,7 @@ FLASH_SIZE ?= FORKNAME = cleanflight -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENWIIF1 ALIENWIIF3 COLIBRI_RACE RMDO +VALID_TARGETS = ALIENWIIF1 ALIENWIIF3 CC3D CHEBUZZF3 CJMCU COLIBRI_RACE EUSTM32F103RC NAZE NAZE32PRO OLIMEXINO PORT103R RMDO SPARKY SPRACINGF3 STM32F3DISCOVERY # Valid targets for OP BootLoader support OPBL_VALID_TARGETS = CC3D @@ -47,9 +47,9 @@ OPBL_VALID_TARGETS = CC3D ifeq ($(FLASH_SIZE),) ifeq ($(TARGET),$(filter $(TARGET),CJMCU)) FLASH_SIZE = 64 -else ifeq ($(TARGET),$(filter $(TARGET),NAZE CC3D ALIENWIIF1 OLIMEXINO RMDO)) +else ifeq ($(TARGET),$(filter $(TARGET),ALIENWIIF1 CC3D NAZE OLIMEXINO RMDO)) FLASH_SIZE = 128 -else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE)) +else ifeq ($(TARGET),$(filter $(TARGET),ALIENWIIF3 CHEBUZZF3 COLIBRI_RACE EUSTM32F103RC NAZE32PRO PORT103R SPARKY SPRACINGF3 STM32F3DISCOVERY)) FLASH_SIZE = 256 else $(error FLASH_SIZE not configured for target) @@ -74,7 +74,7 @@ USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c)) CSOURCES := $(shell find $(SRC_DIR) -name '*.c') -ifeq ($(TARGET),$(filter $(TARGET),STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 SPARKY ALIENWIIF3 COLIBRI_RACE RMDO)) +ifeq ($(TARGET),$(filter $(TARGET),ALIENWIIF3 CHEBUZZF3 COLIBRI_RACE NAZE32PRO RMDO SPARKY SPRACINGF3 STM32F3DISCOVERY)) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver @@ -218,7 +218,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ VPATH := $(VPATH):$(TARGET_DIR) -COMMON_SRC = build_config.c \ +COMMON_SRC = build_config.c \ debug.c \ version.c \ $(TARGET_SRC) \ @@ -265,7 +265,8 @@ COMMON_SRC = build_config.c \ $(CMSIS_SRC) \ $(DEVICE_STDPERIPH_SRC) -HIGHEND_SRC = \ +HIGHEND_SRC = \ + flight/gtune.c \ flight/navigation.c \ flight/gps_conversion.c \ common/colorconversion.c \ @@ -282,7 +283,7 @@ HIGHEND_SRC = \ blackbox/blackbox.c \ blackbox/blackbox_io.c -VCP_SRC = \ +VCP_SRC = \ vcp/hw_config.c \ vcp/stm32_it.c \ vcp/usb_desc.c \ @@ -292,7 +293,7 @@ VCP_SRC = \ vcp/usb_pwr.c \ drivers/serial_usb_vcp.c -NAZE_SRC = startup_stm32f10x_md_gcc.S \ +NAZE_SRC = startup_stm32f10x_md_gcc.S \ drivers/accgyro_adxl345.c \ drivers/accgyro_bma280.c \ drivers/accgyro_l3g4200d.c \ @@ -333,9 +334,9 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \ $(HIGHEND_SRC) \ $(COMMON_SRC) -ALIENWIIF1_SRC = $(NAZE_SRC) +ALIENWIIF1_SRC = $(NAZE_SRC) -EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ +EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ drivers/accgyro_adxl345.c \ drivers/accgyro_bma280.c \ drivers/accgyro_l3g4200d.c \ @@ -377,7 +378,7 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ PORT103R_SRC = $(EUSTM32F103RC_SRC) -OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ +OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ drivers/adc.c \ @@ -414,7 +415,7 @@ $(error OPBL specified with a unsupported target) endif endif -CJMCU_SRC = \ +CJMCU_SRC = \ startup_stm32f10x_md_gcc.S \ drivers/adc.c \ drivers/adc_stm32f10x.c \ @@ -434,11 +435,12 @@ CJMCU_SRC = \ drivers/timer.c \ drivers/timer_stm32f10x.c \ hardware_revision.c \ + flight/gtune.c \ blackbox/blackbox.c \ blackbox/blackbox_io.c \ $(COMMON_SRC) -CC3D_SRC = \ +CC3D_SRC = \ startup_stm32f10x_md_gcc.S \ drivers/accgyro_mpu.c \ drivers/accgyro_spi_mpu6000.c \ @@ -472,7 +474,7 @@ CC3D_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) -STM32F30x_COMMON_SRC = \ +STM32F30x_COMMON_SRC = \ startup_stm32f30x_md_gcc.S \ drivers/adc.c \ drivers/adc_stm32f30x.c \ @@ -492,13 +494,13 @@ STM32F30x_COMMON_SRC = \ drivers/timer.c \ drivers/timer_stm32f30x.c -NAZE32PRO_SRC = \ +NAZE32PRO_SRC = \ $(STM32F30x_COMMON_SRC) \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ $(VCP_SRC) -STM32F3DISCOVERY_COMMON_SRC = \ +STM32F3DISCOVERY_COMMON_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/accgyro_l3gd20.c \ drivers/accgyro_l3gd20.c \ @@ -506,7 +508,7 @@ STM32F3DISCOVERY_COMMON_SRC = \ drivers/compass_hmc5883l.c \ $(VCP_SRC) -STM32F3DISCOVERY_SRC = \ +STM32F3DISCOVERY_SRC = \ $(STM32F3DISCOVERY_COMMON_SRC) \ drivers/accgyro_adxl345.c \ drivers/accgyro_bma280.c \ @@ -520,12 +522,12 @@ STM32F3DISCOVERY_SRC = \ $(HIGHEND_SRC) \ $(COMMON_SRC) -CHEBUZZF3_SRC = \ +CHEBUZZF3_SRC = \ $(STM32F3DISCOVERY_SRC) \ $(HIGHEND_SRC) \ $(COMMON_SRC) -COLIBRI_RACE_SRC = \ +COLIBRI_RACE_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/display_ug2864hsweg01.c \ drivers/accgyro_mpu.c \ @@ -538,7 +540,7 @@ COLIBRI_RACE_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) -SPARKY_SRC = \ +SPARKY_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/display_ug2864hsweg01.c \ drivers/accgyro_mpu.c \ @@ -550,9 +552,10 @@ SPARKY_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) -ALIENWIIF3_SRC = $(SPARKY_SRC) +ALIENWIIF3_SRC = \ + $(SPARKY_SRC) -RMDO_SRC = \ +RMDO_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ @@ -565,7 +568,7 @@ RMDO_SRC = \ $(HIGHEND_SRC) \ $(COMMON_SRC) -SPRACINGF3_SRC = \ +SPRACINGF3_SRC = \ $(STM32F30x_COMMON_SRC) \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ diff --git a/docs/Gtune.md b/docs/Gtune.md new file mode 100644 index 000000000..28610665c --- /dev/null +++ b/docs/Gtune.md @@ -0,0 +1,47 @@ +# G-Tune instructions. + +The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) +http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html +http://diydrones.com/profiles/blogs/zero-pid-tunes-for-multirotors-part-2 +http://www.multiwii.com/forum/viewtopic.php?f=8&t=5190 + +The G-Tune functionality for Cleanflight is ported from the Harakiri firmware. + +- Safety preamble: Use at your own risk - + +The implementation you have here is quiet different and just for adjusting the P values of ROLL/PITCH/YAW in Acro mode. +When flying in Acro mode (yaw tune in other modes possible as well - see below) you can activate G-Tune with an AUX box (switch) while the copter is armed. +It will start tuning the wanted / possible axes (see below) in a predefined range (see below). +After activation you will probably notice nothing! That means G-Tune will not start shaking your copter, you will have to do it (or simply fly and let it work). +The G-Tune is based on the gyro error so it is only active when you give no RC input (that would be an additional error). So if you just roll only pitch +and yaw are tuned. If you stop rolling G-Tune will wait ca. 450ms to let the axis settle and then start tuning that axis again. All axes are treated independently. +The easiest way to tune all axes at once is to do some air-jumps with the copter in Acro (RC centered and G-Tune activated... of course..). +You can set a too high P for the axes as default in the GUI, when the copter starts shaking the wobbles will be detected and P tuned down (be careful with the strength setting though - see below). +Yaw tune is disabled in any copter with less than 4 motors (like tricopters). +G-Tune in Horizon or Level mode will just affect Yaw axis (if more than 3 motors...) +You will see the results in the GUI - the tuning results will only be saved if you enable G-Tune mode while the copter is disarmed and G-Tune was used before when armed. You also can save the configuration in an alternative way (like hitting save button in the GUI, casting an eepromwrite with trimming, acc calibration etc.) +TPA and G-Tune: It is not tested and will most likely not result into something good. However G-Tune might be able to replace TPA for you. + +## Parameters and their function: + + gtune_loP_rll = 10 [0..200] Lower limit of ROLL P during G-Tune. Note "10" means "1.0" in the GUI. + gtune_loP_ptch = 10 [0..200] Lower limit of PITCH P during G-Tune. Note "10" means "1.0" in the GUI. + gtune_loP_yw = 10 [0..200] Lower limit of YAW P during G-Tune. Note "10" means "1.0" in the GUI. + gtune_hiP_rll = 100 [0..200] Higher limit of ROLL P during G-Tune. 0 Disables tuning for that axis. Note "100" means "10.0" in the GUI. + gtune_hiP_ptch = 100 [0..200] Higher limit of PITCH P during G-Tune. 0 Disables tuning for that axis. Note "100" means "10.0" in the GUI. + gtune_hiP_yw = 100 [0..200] Higher limit of YAW P during G-Tune. 0 Disables tuning for that axis. Note "100" means "10.0" in the GUI. + gtune_pwr = 0 [0..10] Strength of adjustment + gtune_settle_time = 450 [200..1000] Settle time in ms + gtune_average_cycles = 16 [8..128] Number of looptime cycles used for gyro average calcullation + +So you have lower and higher limits for each P for every axis. The preset range (GUI: 1.0 - 10.0) is quiet broad to represent most setups. +If you want tighter or more loose ranges change them here. gtune_loP_XXX can be configured lower than "10" that means a P of "1.0" in the GUI. So you can have "Zero P" but you may get sluggish initial control. +If you want to exclude one axis from the tuning you must set gtune_hiP_XXX to zero. Let's say you want to disable yaw tuning write in CLI +"set gtune_hiP_yw = 0". Note: The MultiWii Wiki advises you to trim the yaw axis on your transmitter. If you have done so (yaw not neutral on your RC) +yaw tuning will be disabled. + +Setting the strength of tuning: +gtune_pwr [0..10] Strength of adjustment. +My small copter works fine with 0 and doesn't like a value of "3". My big copter likes "gtune_pwr = 5". It shifts the tuning to higher values and if too high can +diminish the wobble blocking! So start with 0 (default). If you feel your resulting P is always too low for you increase gtune_pwr. You will see it getting a little shaky +if value too high. diff --git a/docs/Modes.md b/docs/Modes.md index 75b8ca6d7..3e8e78d73 100644 --- a/docs/Modes.md +++ b/docs/Modes.md @@ -27,6 +27,7 @@ auxillary receiver channels and other events such as failsafe detection. | 20 | 19 | TELEMETRY | Enable telemetry via switch | | 22 | 21 | SONAR | Altitude hold mode (sonar sensor only) | | 26 | 25 | BLACKBOX | Enable BlackBox logging | +| 27 | 26 | GTUNE | G-Tune - auto tuning of Pitch/Roll/Yaw P values | ## Mode details diff --git a/docs/PID tuning.md b/docs/PID tuning.md index 63f8498cf..453de3ab7 100644 --- a/docs/PID tuning.md +++ b/docs/PID tuning.md @@ -150,10 +150,11 @@ For the ALIENWII32 targets the gyroscale is removed for more yaw authority. This PID Controller 5 is an port of the PID controller from the Harakiri firmware. -The algorithm is leveraging more floating point math. This PID controller also compensates for different looptimes on roll and pitch. It likely don't need retuning of the PID values when looptime is changing. Actually there are two settings hardcoded which are configurable via the GUI in Harakiri: +The algorithm is leveraging more floating point math. This PID controller also compensates for different looptimes on roll and pitch. It likely don't need retuning of the PID values when looptime is changing. There are two additional settings which are configurable via the CLI in Harakiri: - OLD_YAW 0 // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw. - MAIN_CUT_HZ 12.0f // (default 12Hz, Range 1-50Hz) + set dterm_cut_hz = 0 [1-50Hz] Cut Off Frequency for D term of main PID controller + (default of 0 equals to 12Hz which was the hardcoded setting in previous Cleanflight versions) + set pid5_oldyw = 0 [0/1] 0 = multiwii 2.3 yaw (default), 1 = older yaw The PID controller is flight tested and running well with the default PID settings. If you want do acrobatics start slowly. diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index bd7b482e8..e279a0695 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1142,6 +1142,10 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data) blackboxWrite(data->inflightAdjustment.adjustmentFunction); blackboxWriteSignedVB(data->inflightAdjustment.newValue); } + case FLIGHT_LOG_EVENT_GTUNE_RESULT: + blackboxWrite(data->gtuneCycleResult.gtuneAxis); + blackboxWriteSignedVB(data->gtuneCycleResult.gtuneGyroAVG); + blackboxWriteS16(data->gtuneCycleResult.gtuneNewP); break; case FLIGHT_LOG_EVENT_LOGGING_RESUME: blackboxWriteUnsignedVB(data->loggingResume.logIteration); diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 4da938e3d..e3c23f80e 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -105,6 +105,7 @@ typedef enum FlightLogEvent { FLIGHT_LOG_EVENT_SYNC_BEEP = 0, FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13, FLIGHT_LOG_EVENT_LOGGING_RESUME = 14, + FLIGHT_LOG_EVENT_GTUNE_RESULT = 20, FLIGHT_LOG_EVENT_LOG_END = 255 } FlightLogEvent; @@ -126,11 +127,18 @@ typedef struct flightLogEvent_loggingResume_t { #define FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG 128 +typedef struct flightLogEvent_gtuneCycleResult_t { + uint8_t gtuneAxis; + int32_t gtuneGyroAVG; + int16_t gtuneNewP; +} flightLogEvent_gtuneCycleResult_t; + typedef union flightLogEventData_t { flightLogEvent_syncBeep_t syncBeep; flightLogEvent_inflightAdjustment_t inflightAdjustment; flightLogEvent_loggingResume_t loggingResume; + flightLogEvent_gtuneCycleResult_t gtuneCycleResult; } flightLogEventData_t; typedef struct flightLogEvent_t diff --git a/src/main/config/config.c b/src/main/config/config.c index 5c324f420..c6de4da2f 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -75,8 +75,6 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse); -#define FLASH_TO_RESERVE_FOR_CONFIG 0x800 - #if !defined(FLASH_SIZE) #error "Flash size not defined for target. (specify in KB)" #endif @@ -118,6 +116,12 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es #error "Flash page count not defined for target." #endif +#if FLASH_SIZE <= 128 +#define FLASH_TO_RESERVE_FOR_CONFIG 0x800 +#else +#define FLASH_TO_RESERVE_FOR_CONFIG 0x1000 +#endif + // 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)) @@ -128,7 +132,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 105; +static const uint8_t EEPROM_CONF_VERSION = 106; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -187,6 +191,20 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->A_level = 5.0f; pidProfile->H_level = 3.0f; pidProfile->H_sensitivity = 75; + + pidProfile->pid5_oldyw = 0; + +#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. + pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune. + pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis. + pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis. + pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis. + pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment + pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms + pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation +#endif } #ifdef GPS diff --git a/src/main/config/runtime_config.h b/src/main/config/runtime_config.h index 857ebea59..6b4dee82e 100644 --- a/src/main/config/runtime_config.h +++ b/src/main/config/runtime_config.h @@ -42,6 +42,7 @@ typedef enum { PASSTHRU_MODE = (1 << 8), SONAR_MODE = (1 << 9), FAILSAFE_MODE = (1 << 10), + GTUNE_MODE = (1 << 11), } flightModeFlags_e; extern uint16_t flightModeFlags; diff --git a/src/main/flight/gtune.c b/src/main/flight/gtune.c new file mode 100644 index 000000000..d32a93ad8 --- /dev/null +++ b/src/main/flight/gtune.c @@ -0,0 +1,211 @@ +/* + * 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 + +#include "platform.h" + +#ifdef GTUNE + +#include "common/axis.h" +#include "common/maths.h" + +#include "drivers/system.h" +#include "drivers/sensor.h" +#include "drivers/accgyro.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/acceleration.h" + +#include "flight/pid.h" +#include "flight/imu.h" + +#include "config/config.h" +#include "blackbox/blackbox.h" + +#include "io/rc_controls.h" + +#include "config/runtime_config.h" + +extern uint16_t cycleTime; +extern uint8_t motorCount; + +/* + **************************************************************************** + *** G_Tune *** + **************************************************************************** + G_Tune Mode + This is the multiwii implementation of ZERO-PID Algorithm + http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html + The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) + + You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution. + */ + +/* + version 1.0.0: MIN & Maxis & Tuned Band + version 1.0.1: + a. error is gyro reading not rc - gyro. + b. OldError = Error no averaging. + c. No Min Maxis BOUNDRY + version 1.0.2: + a. no boundaries + b. I - Factor tune. + c. time_skip + + Crashpilot: Reduced to just P tuning in a predefined range - so it is not "zero pid" anymore. + Tuning is limited to just work when stick is centered besides that YAW is tuned in non Acro as well. + See also: + http://diydrones.com/profiles/blogs/zero-pid-tunes-for-multirotors-part-2 + http://www.multiwii.com/forum/viewtopic.php?f=8&t=5190 + Gyrosetting 2000DPS + GyroScale = (1 / 16,4 ) * RADX(see board.h) = 0,001064225154 digit per rad/s + + 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. + pidProfile->gtune_lolimP[YAW] = 10; [0..200] Lower limit of YAW P during G tune. + pidProfile->gtune_hilimP[ROLL] = 100; [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axisis. + pidProfile->gtune_hilimP[PITCH] = 100; [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axisis. + pidProfile->gtune_hilimP[YAW] = 100; [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axisis. + pidProfile->gtune_pwr = 0; [0..10] Strength of adjustment + pidProfile->gtune_settle_time = 450; [200..1000] Settle time in ms + pidProfile->gtune_average_cycles = 16; [8..128] Number of looptime cycles used for gyro average calculation +*/ + +static pidProfile_t *pidProfile; +static int16_t delay_cycles; +static int16_t time_skip[3]; +static int16_t OldError[3], result_P64[3]; +static int32_t AvgGyro[3]; +static bool floatPID; + +void updateDelayCycles(void) +{ + delay_cycles = -(((int32_t)pidProfile->gtune_settle_time * 1000) / cycleTime); +} + +void init_Gtune(pidProfile_t *pidProfileToTune) +{ + uint8_t i; + + pidProfile = pidProfileToTune; + if (pidProfile->pidController == 2) { + floatPID = true; // LuxFloat is using float values for PID settings + } else { + floatPID = false; + } + updateDelayCycles(); + for (i = 0; i < 3; i++) { + if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning + pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter + } + if (floatPID) { + if((pidProfile->P_f[i] * 10.0f) < pidProfile->gtune_lolimP[i]) { + pidProfile->P_f[i] = (float)(pidProfile->gtune_lolimP[i] / 10.0f); + } + result_P64[i] = (int16_t)pidProfile->P_f[i] << 6; // 6 bit extra resolution for P. + } else { + if(pidProfile->P8[i] < pidProfile->gtune_lolimP[i]) { + pidProfile->P8[i] = pidProfile->gtune_lolimP[i]; + } + result_P64[i] = (int16_t)pidProfile->P8[i] << 6; // 6 bit extra resolution for P. + } + OldError[i] = 0; + time_skip[i] = delay_cycles; + } +} + +void calculate_Gtune(uint8_t axis) +{ + int16_t error, diff_G, threshP; + + if(rcCommand[axis] || (axis != FD_YAW && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)))) { // Block tuning on stick input. Always allow G-Tune on YAW, Roll & Pitch only in acromode + OldError[axis] = 0; + time_skip[axis] = delay_cycles; // Some settle time after stick center. default 450ms + } else { + if (!time_skip[axis]) AvgGyro[axis] = 0; + time_skip[axis]++; + if (time_skip[axis] > 0) { + if (axis == FD_YAW) { + AvgGyro[axis] += 32 * ((int16_t)gyroADC[axis] / 32); // Chop some jitter and average + } else { + AvgGyro[axis] += 128 * ((int16_t)gyroADC[axis] / 128); // Chop some jitter and average + } + } + if (time_skip[axis] == pidProfile->gtune_average_cycles) { // Looptime cycles for gyro average calculation. default 16. + AvgGyro[axis] /= time_skip[axis]; // AvgGyro[axis] has now very clean gyrodata + time_skip[axis] = 0; + if (axis == FD_YAW) { + threshP = 20; + error = -AvgGyro[axis]; + } else { + threshP = 10; + error = AvgGyro[axis]; + } + if (pidProfile->gtune_hilimP[axis] && error && OldError[axis] && error != OldError[axis]) { // Don't run when not needed or pointless to do so + diff_G = ABS(error) - ABS(OldError[axis]); + if ((error > 0 && OldError[axis] > 0) || (error < 0 && OldError[axis] < 0)) { + if (diff_G > threshP) { + if (axis == FD_YAW) { + result_P64[axis] += 256 + pidProfile->gtune_pwr; // YAW ends up at low limit on float PID, give it some more to work with. + } else { + result_P64[axis] += 64 + pidProfile->gtune_pwr; // Shift balance a little on the plus side. + } + } else { + if (diff_G < -threshP) { + if (axis == FD_YAW) { + result_P64[axis] -= 64 + pidProfile->gtune_pwr; + } else { + result_P64[axis] -= 32; + } + } + } + } else { + if (ABS(diff_G) > threshP && axis != FD_YAW) { + result_P64[axis] -= 32; // Don't use antiwobble for YAW + } + } + int16_t newP = constrain((result_P64[axis] >> 6), (int16_t)pidProfile->gtune_lolimP[axis], (int16_t)pidProfile->gtune_hilimP[axis]); + +#ifdef BLACKBOX + if (feature(FEATURE_BLACKBOX)) { + flightLogEvent_gtuneCycleResult_t eventData; + + eventData.gtuneAxis = axis; + eventData.gtuneGyroAVG = AvgGyro[axis]; + eventData.gtuneNewP = newP; // for float PID the logged P value is still mutiplyed by 10 + blackboxLogEvent(FLIGHT_LOG_EVENT_GTUNE_RESULT, (flightLogEventData_t*)&eventData); + } +#endif + + if (floatPID) { + pidProfile->P_f[axis] = (float)newP / 10.0f; // new P value for float PID + } else { + pidProfile->P8[axis] = newP; // new P value + } + } + OldError[axis] = error; + } + } +} + +#endif + diff --git a/src/main/flight/gtune.h b/src/main/flight/gtune.h new file mode 100644 index 000000000..f580c7c12 --- /dev/null +++ b/src/main/flight/gtune.h @@ -0,0 +1,21 @@ +/* + * 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 + +void init_Gtune(pidProfile_t *pidProfileToTune); +void calculate_Gtune(uint8_t axis); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 856c01db5..11b72d1ba 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -41,6 +41,7 @@ #include "flight/pid.h" #include "flight/imu.h" #include "flight/navigation.h" +#include "flight/gtune.h" #include "flight/filter.h" #include "config/runtime_config.h" @@ -208,6 +209,12 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa // -----calculate total PID output axisPID[axis] = constrain(lrintf(PTerm + ITerm + DTerm), -1000, 1000); +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(axis); + } +#endif + #ifdef BLACKBOX axisPID_P[axis] = PTerm; axisPID_I[axis] = ITerm; @@ -297,6 +304,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa DTerm = (deltaSum * dynD8[axis]) / 32; axisPID[axis] = PTerm + ITerm - DTerm; +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(axis); + } +#endif + #ifdef BLACKBOX axisPID_P[axis] = PTerm; axisPID_I[axis] = ITerm; @@ -382,6 +395,12 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control axisPID[axis] = PTerm + ITerm - DTerm; +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(axis); + } +#endif + #ifdef BLACKBOX axisPID_P[axis] = PTerm; axisPID_I[axis] = ITerm; @@ -411,6 +430,12 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control axisPID[FD_YAW] = PTerm + ITerm; +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(FD_YAW); + } +#endif + #ifdef BLACKBOX axisPID_P[FD_YAW] = PTerm; axisPID_I[FD_YAW] = ITerm; @@ -498,6 +523,12 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con DTerm = (deltaSum * dynD8[axis]) / 32; axisPID[axis] = PTerm + ITerm - DTerm; +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(axis); + } +#endif + #ifdef BLACKBOX axisPID_P[axis] = PTerm; axisPID_I[axis] = ITerm; @@ -526,6 +557,11 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con axisPID[FD_YAW] = PTerm + ITerm; +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(FD_YAW); + } +#endif #ifdef BLACKBOX axisPID_P[FD_YAW] = PTerm; @@ -545,7 +581,11 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) uint8_t axis; float ACCDeltaTimeINS, FLOATcycleTime, Mwii3msTimescale; - MainDptCut = RCconstPI / constrain(pidProfile->dterm_cut_hz, 1, 50); // maincuthz (default 0 (disabled), Range 1-50Hz) + if (pidProfile->dterm_cut_hz) { + MainDptCut = RCconstPI / constrain(pidProfile->dterm_cut_hz, 1, 50); // dterm_cut_hz (default 0, Range 1-50Hz) + } else { + MainDptCut = RCconstPI / 12.0f; // default is 12Hz to maintain initial behavior of PID5 + } FLOATcycleTime = (float)constrain(cycleTime, 1, 100000); // 1us - 100ms ACCDeltaTimeINS = FLOATcycleTime * 0.000001f; // ACCDeltaTimeINS is in seconds now RCfactor = ACCDeltaTimeINS / (MainDptCut + ACCDeltaTimeINS); // used for pt1 element @@ -557,7 +597,7 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) for (axis = 0; axis < 2; axis++) { int32_t tmp = (int32_t)((float)gyroADC[axis] * 0.3125f); // Multiwii masks out the last 2 bits, this has the same idea gyroADCQuant = (float)tmp * 3.2f; // but delivers more accuracy and also reduces jittery flight - rcCommandAxis = (float)rcCommand[axis]; // Calculate common values for pid controllers + rcCommandAxis = (float)rcCommand[axis]; // Calculate common values for pid controllers if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { #ifdef GPS error = constrain(2.0f * rcCommandAxis + GPS_angle[axis], -((int) max_angle_inclination), +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; @@ -609,6 +649,12 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) axisPID[axis] = lrintf(PTerm + ITerm - DTerm); // Round up result. +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(axis); + } +#endif + #ifdef BLACKBOX axisPID_P[axis] = PTerm; axisPID_I[axis] = ITerm; @@ -619,7 +665,7 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) Mwii3msTimescale = (int32_t)FLOATcycleTime & (int32_t)~3; // Filter last 2 bit jitter Mwii3msTimescale /= 3000.0f; - if (OLD_YAW) { // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw. hardcoded for now + if (pidProfile->pid5_oldyw) { // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw PTerm = ((int32_t)pidProfile->P8[FD_YAW] * (100 - (int32_t)controlRateConfig->rates[FD_YAW] * (int32_t)ABS(rcCommand[FD_YAW]) / 500)) / 100; int32_t tmp = lrintf(gyroADC[FD_YAW] * 0.25f); PTerm = rcCommand[FD_YAW] - tmp * PTerm / 80; @@ -656,6 +702,12 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) axisPID[FD_YAW] = PTerm + ITerm; axisPID[FD_YAW] = lrintf(axisPID[FD_YAW]); // Round up result. +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(FD_YAW); + } +#endif + #ifdef BLACKBOX axisPID_P[FD_YAW] = PTerm; axisPID_I[FD_YAW] = ITerm; @@ -776,6 +828,12 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat // -----calculate total PID output axisPID[axis] = PTerm + ITerm + DTerm; +#ifdef GTUNE + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + calculate_Gtune(axis); + } +#endif + #ifdef BLACKBOX axisPID_P[axis] = PTerm; axisPID_I[axis] = ITerm; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 3ec0004e9..52c50eb8e 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -61,10 +61,21 @@ typedef struct pidProfile_s { float A_level; float H_level; uint8_t H_sensitivity; + uint16_t yaw_p_limit; // set P term limit (fixed value was 300) uint8_t dterm_cut_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5 uint8_t pterm_cut_hz; // Used for fitlering Pterm noise on noisy frames uint8_t gyro_cut_hz; // Used for soft gyro filtering + + uint8_t pid5_oldyw; // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw + +#ifdef GTUNE + uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune + uint8_t gtune_hilimP[3]; // [0..200] Higher limit of P during G tune. 0 Disables tuning for that axis. + uint8_t gtune_pwr; // [0..10] Strength of adjustment + uint16_t gtune_settle_time; // [200..1000] Settle time in ms + uint8_t gtune_average_cycles; // [8..128] Number of looptime cycles used for gyro average calculation +#endif } pidProfile_t; #define DEGREES_TO_DECIDEGREES(angle) (angle * 10) diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h index dbe552cbe..269cf51ca 100644 --- a/src/main/io/rc_controls.h +++ b/src/main/io/rc_controls.h @@ -48,6 +48,7 @@ typedef enum { BOXSERVO3, BOXBLACKBOX, BOXFAILSAFE, + BOXGTUNE, CHECKBOX_ITEM_COUNT } boxId_e; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 812d69470..737e373b4 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -514,6 +514,20 @@ const clivalue_t valueTable[] = { { "pterm_cut_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pterm_cut_hz, 0, 200 }, { "gyro_cut_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gyro_cut_hz, 0, 200 }, + { "pid5_oldyw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pid5_oldyw, 0, 1 }, + +#ifdef GTUNE + { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], 10, 200 }, + { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], 10, 200 }, + { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], 10, 200 }, + { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], 0, 200 }, + { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], 0, 200 }, + { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], 0, 200 }, + { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, 0, 10 }, + { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, 200, 1000 }, + { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, 8, 128 }, +#endif + #ifdef BLACKBOX { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 }, { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 }, diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index fa2a3c14f..62fc279a7 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -340,7 +340,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { BOXGOV, "GOVERNOR;", 18 }, { BOXOSD, "OSD SW;", 19 }, { BOXTELEMETRY, "TELEMETRY;", 20 }, - //{ BOXAUTOTUNE, "AUTOTUNE;", 21 }, + { BOXGTUNE, "GTUNE;", 21 }, { BOXSONAR, "SONAR;", 22 }, { BOXSERVO1, "SERVO1;", 23 }, { BOXSERVO2, "SERVO2;", 24 }, @@ -699,6 +699,10 @@ void mspInit(serialConfig_t *serialConfig) activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE; } +#ifdef GTUNE + activeBoxIds[activeBoxIdCount++] = BOXGTUNE; +#endif + memset(mspPorts, 0x00, sizeof(mspPorts)); mspAllocateSerialPorts(serialConfig); } @@ -817,6 +821,7 @@ static bool processOutCommand(uint8_t cmdMSP) IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGOV)) << BOXGOV | IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSD)) << BOXOSD | IS_ENABLED(IS_RC_MODE_ACTIVE(BOXTELEMETRY)) << BOXTELEMETRY | + IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGTUNE)) << BOXGTUNE | IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR | IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM | IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX | diff --git a/src/main/mw.c b/src/main/mw.c index 2ce13d722..59d196b1e 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -70,6 +70,7 @@ #include "flight/imu.h" #include "flight/altitudehold.h" #include "flight/failsafe.h" +#include "flight/gtune.h" #include "flight/navigation.h" #include "flight/filter.h" @@ -121,6 +122,30 @@ void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsD saveConfigAndNotify(); } +#ifdef GTUNE + +void updateGtuneState(void) +{ + static bool GTuneWasUsed = false; + + if (IS_RC_MODE_ACTIVE(BOXGTUNE)) { + if (!FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + ENABLE_FLIGHT_MODE(GTUNE_MODE); + init_Gtune(¤tProfile->pidProfile); + GTuneWasUsed = true; + } + if (!FLIGHT_MODE(GTUNE_MODE) && !ARMING_FLAG(ARMED) && GTuneWasUsed) { + saveConfigAndNotify(); + GTuneWasUsed = false; + } + } else { + if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { + DISABLE_FLIGHT_MODE(GTUNE_MODE); + } + } +} +#endif + bool isCalibrating() { #ifdef BARO @@ -759,6 +784,10 @@ void loop(void) } #endif +#ifdef GTUNE + updateGtuneState(); +#endif + #if defined(BARO) || defined(SONAR) if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) { diff --git a/src/main/target/ALIENWIIF3/target.h b/src/main/target/ALIENWIIF3/target.h index 0011ea4a3..ff3716f1d 100644 --- a/src/main/target/ALIENWIIF3/target.h +++ b/src/main/target/ALIENWIIF3/target.h @@ -113,6 +113,7 @@ //#define BLACKBOX #define SERIAL_RX //#define GPS +#define GTUNE //#define DISPLAY #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 5744a5c1d..e30f41582 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -112,6 +112,7 @@ #define TELEMETRY #define SERIAL_RX #define SONAR +#define GTUNE #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index f7bca39e1..330a90fc1 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -119,6 +119,7 @@ #endif #define BLACKBOX +#define GTUNE #define TELEMETRY #define SERIAL_RX #define USE_SERVOS diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index 20e1bcc58..4c0649f38 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -40,8 +40,8 @@ #define GYRO #define USE_GYRO_MPU6050 -#define MAG -#define USE_MAG_HMC5883 +//#define MAG +//#define USE_MAG_HMC5883 #define BRUSHED_MOTORS @@ -75,4 +75,5 @@ #endif //#undef USE_CLI +#define GTUNE //#define BLACKBOX diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 924cdbf39..215f6212a 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -140,6 +140,7 @@ #define BLACKBOX #define GPS +#define GTUNE #define LED_STRIP #define LED_STRIP_TIMER TIM16 diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index 2786a9cb6..cb751dd75 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -122,6 +122,7 @@ #define LED_STRIP_TIMER TIM3 #define BLACKBOX +#define GTUNE #define TELEMETRY #define SERIAL_RX #define USE_SERVOS diff --git a/src/main/target/NAZE32PRO/target.h b/src/main/target/NAZE32PRO/target.h index 1359fa140..7cb85713d 100644 --- a/src/main/target/NAZE32PRO/target.h +++ b/src/main/target/NAZE32PRO/target.h @@ -40,10 +40,11 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_1) -#define GPS #define BLACKBOX -#define TELEMETRY +#define GPS +#define GTUNE #define SERIAL_RX +#define TELEMETRY #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index d80b4360f..766c64cb7 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -144,12 +144,14 @@ #define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 #define LED0 -#define GPS + #define LED_STRIP #define LED_STRIP_TIMER TIM3 #define BLACKBOX -#define TELEMETRY +#define GPS +#define GTUNE #define SERIAL_RX +#define TELEMETRY #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 59c695f17..52bca09b4 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -108,10 +108,11 @@ #define CURRENT_METER_ADC_CHANNEL ADC_Channel_4 #define BLACKBOX -#define TELEMETRY -#define SERIAL_RX #define GPS +#define GTUNE #define DISPLAY +#define SERIAL_RX +#define TELEMETRY #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index bb99a9479..9ed3d3cca 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -156,11 +156,12 @@ #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn -#define GPS #define BLACKBOX -#define TELEMETRY -#define SERIAL_RX #define DISPLAY +#define GPS +#define GTUNE +#define SERIAL_RX +#define TELEMETRY #define USE_SERVOS #define USE_CLI diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 5eb5f969e..ffefe5ede 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -91,6 +91,7 @@ #define BLACKBOX #define GPS +#define GTUNE #define LED_STRIP #define LED_STRIP_TIMER TIM16 #define TELEMETRY diff --git a/src/main/target/stm32_flash_f103_128k.ld b/src/main/target/stm32_flash_f103_128k.ld index 83debfd9d..48441c237 100644 --- a/src/main/target/stm32_flash_f103_128k.ld +++ b/src/main/target/stm32_flash_f103_128k.ld @@ -9,7 +9,7 @@ ***************************************************************************** */ -/* Specify the memory areas. Flash is limited for last 2K for configuration storage */ +/* Specify the memory areas. */ MEMORY { FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 126K /* last 2kb used for config storage */ diff --git a/src/main/target/stm32_flash_f103_128k_opbl.ld b/src/main/target/stm32_flash_f103_128k_opbl.ld index 49cc3b29e..a8fad3a5f 100644 --- a/src/main/target/stm32_flash_f103_128k_opbl.ld +++ b/src/main/target/stm32_flash_f103_128k_opbl.ld @@ -9,7 +9,7 @@ ***************************************************************************** */ -/* Specify the memory areas. Flash is limited for last 2K for configuration storage */ +/* Specify the memory areas. */ MEMORY { FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 126K - 0x03000 /* last 2kb used for config storage first 12k for OP Bootloader*/ diff --git a/src/main/target/stm32_flash_f103_256k.ld b/src/main/target/stm32_flash_f103_256k.ld index ccdccd0b6..0f0c2fe88 100644 --- a/src/main/target/stm32_flash_f103_256k.ld +++ b/src/main/target/stm32_flash_f103_256k.ld @@ -9,10 +9,10 @@ ***************************************************************************** */ -/* Specify the memory areas. Flash is limited for last 2K for configuration storage */ +/* Specify the memory areas. */ MEMORY { - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 254K /* last 2kb used for config storage */ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 252K /* last 4kb used for config storage */ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 48K MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K } diff --git a/src/main/target/stm32_flash_f103_64k.ld b/src/main/target/stm32_flash_f103_64k.ld index e0ceedfac..a72e2b608 100644 --- a/src/main/target/stm32_flash_f103_64k.ld +++ b/src/main/target/stm32_flash_f103_64k.ld @@ -9,7 +9,7 @@ ***************************************************************************** */ -/* Specify the memory areas. Flash is limited for last 2K for configuration storage */ +/* Specify the memory areas. */ MEMORY { FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 62K /* last 2kb used for config storage */ diff --git a/src/main/target/stm32_flash_f303_128k.ld b/src/main/target/stm32_flash_f303_128k.ld index 87b5b85f0..a13c30458 100644 --- a/src/main/target/stm32_flash_f303_128k.ld +++ b/src/main/target/stm32_flash_f303_128k.ld @@ -9,7 +9,7 @@ ***************************************************************************** */ -/* Specify the memory areas */ +/* Specify the memory areas. */ MEMORY { FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 126K /* last 2kb used for config storage */ diff --git a/src/main/target/stm32_flash_f303_256k.ld b/src/main/target/stm32_flash_f303_256k.ld index e25c73a96..2db0e7713 100644 --- a/src/main/target/stm32_flash_f303_256k.ld +++ b/src/main/target/stm32_flash_f303_256k.ld @@ -9,10 +9,10 @@ ***************************************************************************** */ -/* Specify the memory areas */ +/* Specify the memory areas. */ MEMORY { - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 254K /* last 2kb used for config storage */ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 252K /* last 4kb used for config storage */ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 40K MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K }