mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: Turn hold_in_bootloader default as false in reboot
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
20d4b1e53f
commit
8fa4d6200c
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue