mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: Prepare reboot before rebooting via AP_Periph:reboot()
Call AP_Periph:prepare_reboot() before rebooting via AP_Periph:reboot()
This commit is contained in:
parent
e4ba4cc885
commit
79b596d229
|
@ -627,6 +627,7 @@ void AP_Periph_FW::prepare_reboot()
|
||||||
*/
|
*/
|
||||||
void AP_Periph_FW::reboot(bool hold_in_bootloader)
|
void AP_Periph_FW::reboot(bool hold_in_bootloader)
|
||||||
{
|
{
|
||||||
|
prepare_reboot();
|
||||||
hal.scheduler->reboot(hold_in_bootloader);
|
hal.scheduler->reboot(hold_in_bootloader);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue