From f4796c3676cc8f152bb06b0a538318a1ccb74b90 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 24 Aug 2016 01:07:04 +0200 Subject: [PATCH] Drop Betaflight PIDc support for OPBL --- src/main/config/config.c | 4 ++++ src/main/io/serial_cli.c | 2 ++ src/main/io/serial_msp.c | 2 ++ src/main/target/CC3D/target.h | 1 + 4 files changed, 9 insertions(+) diff --git a/src/main/config/config.c b/src/main/config/config.c index f74bf867f..996dd1f20 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -199,7 +199,11 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) static void resetPidProfile(pidProfile_t *pidProfile) { +#if defined(SKIP_PID_FLOAT) + pidProfile->pidController = PID_CONTROLLER_LEGACY; +#else pidProfile->pidController = PID_CONTROLLER_BETAFLIGHT; +#endif pidProfile->P8[ROLL] = 45; pidProfile->I8[ROLL] = 40; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index ff524656e..d26a31047 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -862,7 +862,9 @@ const clivalue_t valueTable[] = { { "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 } }, +#ifndef SKIP_PID_FLOAT { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } }, +#endif { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } }, { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } }, diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 3844595c3..52de0e4ed 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1353,8 +1353,10 @@ static bool processInCommand(void) read16(); break; case MSP_SET_PID_CONTROLLER: +#ifndef SKIP_PID_FLOAT currentProfile->pidProfile.pidController = constrain(read8(), 0, 1); pidSetController(currentProfile->pidProfile.pidController); +#endif break; case MSP_SET_PID: for (i = 0; i < PID_ITEM_COUNT; i++) { diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 4cf679e1e..cdf8ceab1 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -118,6 +118,7 @@ #undef SONAR #undef USE_SOFTSERIAL1 #undef LED_STRIP +#define SKIP_PID_FLOAT #endif #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -- 2.11.4.GIT