From 2546eb15e7e5b72d1b286470033e12795a7d28fe Mon Sep 17 00:00:00 2001 From: Dmitry Rechkin Date: Tue, 1 Mar 2016 13:42:30 -0800 Subject: [PATCH] At some point code has been changed to automatically reset spektrum_sat_bind setting to 0 on hard reboot, which made obsolete 0 option and essentially removed a feature which allowed to request binding on every boot, which, for example, is how toy quadcopters behave. I've added new setting: "spektrum_sat_bind_autoreset" which can accept values: 0 - disabled 1 - enabled (by default, to preserve current behavior) It is convenient, if you send BNF quadcopter to somebody, so they can start flying it without the need to figuring out how cleanflight works, if they are not familiar with it. --- src/main/config/config.c | 2 ++ src/main/io/serial_cli.c | 1 + src/main/rx/rx.h | 1 + src/main/rx/spektrum.c | 3 ++- 4 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 212669a67..48e6ff5db 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -441,6 +441,7 @@ static void resetConf(void) masterConfig.rxConfig.serialrx_provider = 0; masterConfig.rxConfig.sbus_inversion = 1; masterConfig.rxConfig.spektrum_sat_bind = 0; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; masterConfig.rxConfig.midrc = 1500; masterConfig.rxConfig.mincheck = 1100; masterConfig.rxConfig.maxcheck = 1900; @@ -615,6 +616,7 @@ static void resetConf(void) #endif masterConfig.rxConfig.serialrx_provider = 1; masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; masterConfig.escAndServoConfig.minthrottle = 1000; masterConfig.escAndServoConfig.maxthrottle = 2000; masterConfig.motor_pwm_rate = 32000; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 7277f8bad..651946cf4 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -606,6 +606,7 @@ const clivalue_t valueTable[] = { { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } }, { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } }, { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} }, + { "spektrum_sat_bind_autoreset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} }, { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } }, { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } }, diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 99bf4b40c..1d546554c 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -114,6 +114,7 @@ typedef struct rxConfig_s { uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first. uint8_t sbus_inversion; // default sbus (Futaba, FrSKY) is inverted. Support for uninverted OpenLRS (and modified FrSKY) receivers. uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers + uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot uint8_t rssi_channel; uint8_t rssi_scale; uint8_t rssi_ppm_invert; diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 5457607d6..312d188ab 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -227,7 +227,8 @@ void spektrumBind(rxConfig_t *rxConfig) #ifndef HARDWARE_BIND_PLUG // If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config // Don't reset if hardware bind plug is present - if (!isMPUSoftReset()) { + // Reset only when autoreset is enabled + if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) { rxConfig->spektrum_sat_bind = 0; saveConfigAndNotify(); }