mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL: added fs_init() to Util API
This commit is contained in:
parent
680caeb349
commit
20f3a92e50
@ -114,6 +114,12 @@ public:
|
||||
how much free memory do we have in bytes. If unknown return 4096
|
||||
*/
|
||||
virtual uint32_t available_memory(void) { return 4096; }
|
||||
|
||||
/*
|
||||
initialise (or re-initialise) filesystem storage
|
||||
*/
|
||||
virtual bool fs_init(void) { return false; }
|
||||
|
||||
protected:
|
||||
// we start soft_armed false, so that actuators don't send any
|
||||
// values until the vehicle code has fully started
|
||||
|
Loading…
Reference in New Issue
Block a user