|
|
|
@ -75,7 +75,7 @@ void AP_Tuning::check_selector_switch(void)
@@ -75,7 +75,7 @@ void AP_Tuning::check_selector_switch(void)
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
uint16_t selector_in = selchan->get_radio_in(); |
|
|
|
|
if (selector_in >= 1700) { |
|
|
|
|
if (selector_in >= RC_Channel::AUX_PWM_TRIGGER_HIGH) { |
|
|
|
|
// high selector
|
|
|
|
|
if (selector_start_ms == 0) { |
|
|
|
|
selector_start_ms = AP_HAL::millis(); |
|
|
|
@ -90,7 +90,7 @@ void AP_Tuning::check_selector_switch(void)
@@ -90,7 +90,7 @@ void AP_Tuning::check_selector_switch(void)
|
|
|
|
|
changed = false; |
|
|
|
|
need_revert = 0; |
|
|
|
|
} |
|
|
|
|
} else if (selector_in <= 1300) { |
|
|
|
|
} else if (selector_in <= RC_Channel::AUX_PWM_TRIGGER_LOW) { |
|
|
|
|
// low selector
|
|
|
|
|
if (selector_start_ms != 0) { |
|
|
|
|
uint32_t hold_time = AP_HAL::millis() - selector_start_ms; |
|
|
|
|