From 8fa4d6200ce7c1e1a83ca5c8b8badc796516c4f6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Wed, 6 Mar 2024 13:33:01 -0300 Subject: [PATCH] AP_HAL: Turn hold_in_bootloader default as false in reboot MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- libraries/AP_HAL/Scheduler.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL/Scheduler.h b/libraries/AP_HAL/Scheduler.h index 0f047617f0..d8ef0b237e 100644 --- a/libraries/AP_HAL/Scheduler.h +++ b/libraries/AP_HAL/Scheduler.h @@ -70,7 +70,7 @@ public: virtual void set_system_initialized() = 0; virtual bool is_system_initialized() = 0; - virtual void reboot(bool hold_in_bootloader) = 0; + virtual void reboot(bool hold_in_bootloader = false) = 0; /** optional function to stop clock at a given time, used by log replay