AP_HAL: added fs_init() to Util API

This commit is contained in:
Andrew Tridgell 2018-12-28 11:27:19 +11:00
parent 680caeb349
commit 20f3a92e50

View File

@ -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