mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning: use AUX_PWM_TRIGGER_LOW and AUX_PWM_TRIGGER_HIGH
This commit is contained in:
parent
67bdec3325
commit
7430a415fb
|
@ -75,7 +75,7 @@ void AP_Tuning::check_selector_switch(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint16_t selector_in = selchan->get_radio_in();
|
uint16_t selector_in = selchan->get_radio_in();
|
||||||
if (selector_in >= 1700) {
|
if (selector_in >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||||
// high selector
|
// high selector
|
||||||
if (selector_start_ms == 0) {
|
if (selector_start_ms == 0) {
|
||||||
selector_start_ms = AP_HAL::millis();
|
selector_start_ms = AP_HAL::millis();
|
||||||
|
@ -90,7 +90,7 @@ void AP_Tuning::check_selector_switch(void)
|
||||||
changed = false;
|
changed = false;
|
||||||
need_revert = 0;
|
need_revert = 0;
|
||||||
}
|
}
|
||||||
} else if (selector_in <= 1300) {
|
} else if (selector_in <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
|
||||||
// low selector
|
// low selector
|
||||||
if (selector_start_ms != 0) {
|
if (selector_start_ms != 0) {
|
||||||
uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
|
uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
|
||||||
|
|
Loading…
Reference in New Issue