mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
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.
This commit is contained in:
parent
16ca4ff16e
commit
2546eb15e7
4 changed files with 6 additions and 1 deletions
|
@ -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 } },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue