mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
decouple failsafe from the rest of the system.
Note: the pwm_common driver has a dependency on the main failsafe code, the solution is probably to move some of the code into rx_pwm.
This commit is contained in:
parent
aef28c1c08
commit
e969d184e6
29 changed files with 224 additions and 119 deletions
|
@ -181,10 +181,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "yawrate", VAR_UINT8, &cfg.controlRateConfig.yawRate, 0, 100 },
|
||||
{ "tparate", VAR_UINT8, &cfg.dynThrPID, 0, 100},
|
||||
{ "tpa_breakpoint", VAR_UINT16, &cfg.tpaBreakPoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
||||
{ "failsafe_delay", VAR_UINT8, &cfg.failsafe_delay, 0, 200 },
|
||||
{ "failsafe_off_delay", VAR_UINT8, &cfg.failsafe_off_delay, 0, 200 },
|
||||
{ "failsafe_throttle", VAR_UINT16, &cfg.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
||||
{ "failsafe_detect_threshold", VAR_UINT16, &cfg.failsafe_detect_threshold, 100, PWM_RANGE_MAX },
|
||||
{ "failsafe_delay", VAR_UINT8, &cfg.failsafeConfig.failsafe_delay, 0, 200 },
|
||||
{ "failsafe_off_delay", VAR_UINT8, &cfg.failsafeConfig.failsafe_off_delay, 0, 200 },
|
||||
{ "failsafe_throttle", VAR_UINT16, &cfg.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
||||
{ "failsafe_detect_threshold", VAR_UINT16, &cfg.failsafeConfig.failsafe_detect_threshold, 100, PWM_RANGE_MAX },
|
||||
{ "rssi_aux_channel", VAR_INT8, &mcfg.rssi_aux_channel, 0, 4 },
|
||||
{ "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8, &cfg.tri_unarmed_servo, 0, 1 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue