mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: Use new default for reboot
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
16926a2df8
commit
20d4b1e53f
|
@ -486,7 +486,7 @@ void AP_OSD_ParamScreen::update_state_machine()
|
|||
if (_selected_param == SAVE_PARAM) {
|
||||
if (_transition_count >= OSD_HOLD_BUTTON_PRESS_COUNT) {
|
||||
save_parameters();
|
||||
hal.scheduler->reboot(false);
|
||||
hal.scheduler->reboot();
|
||||
} else {
|
||||
save_parameters();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue