Merge pull request #235 from dmitryrechkin/betaflight

Ability to configure spektrum_sat_bind auto reset on hard reboot
This commit is contained in:
borisbstyle 2016-03-02 14:18:54 +01:00
commit 4074b74676
4 changed files with 6 additions and 1 deletions

View File

@ -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;

View File

@ -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 } },

View File

@ -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;

View File

@ -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();
}