mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_OSD: fixes bug introduced by #16477
This commit is contained in:
parent
d12759d20b
commit
bd583452c7
@ -423,8 +423,11 @@ void AP_OSD::update_current_screen()
|
||||
case PWM_RANGE:
|
||||
for (int i=0; i<AP_OSD_NUM_SCREENS; i++) {
|
||||
if (get_screen(i).enabled && get_screen(i).channel_min <= channel_value && get_screen(i).channel_max > channel_value) {
|
||||
if (previous_pwm_screen == i) {
|
||||
break;
|
||||
} else {
|
||||
current_screen = previous_pwm_screen = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user