34 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 36 #pragma GCC optimize ("O2") 49 #if defined(WRITE_IN_THREAD) 57 #if defined(EEPROM_CACHED) 98 AP_HAL::panic(
"EEPROM Error: page not empty after erase\r\n");
117 #if defined(EEPROM_CACHED) 121 #pragma GCC diagnostic push 122 #pragma GCC diagnostic ignored "-Wcast-align" // yes I know 125 #pragma GCC diagnostic pop 138 #if defined(EEPROM_CACHED) 139 return eeprom_buffer[loc];
162 #if defined(EEPROM_CACHED) 163 memmove(dst, &eeprom_buffer[loc], n);
166 uint8_t *ptr_b=(uint8_t *)dst;
173 #pragma GCC diagnostic push 174 #pragma GCC diagnostic ignored "-Wcast-align" 175 uint16_t *ptr_w=(uint16_t *)ptr_b;
176 #pragma GCC diagnostic pop 185 ptr_b=(uint8_t *)ptr_w;
192 #if defined(EEPROM_CACHED) 193 if(eeprom_buffer[loc]==value)
return;
194 eeprom_buffer[loc]=
value;
207 #if defined(EEPROM_CACHED) 208 memmove(&data,&eeprom_buffer[loc & ~1], 2);
214 data = (data & 0x00ff) | (value << 8);
216 data = (data & 0xff00) | value;
223 #if defined(EEPROM_CACHED) 224 memmove(&eeprom_buffer[loc], src, n);
230 uint8_t *ptr_b = (uint8_t *)src;
236 #pragma GCC diagnostic push 237 #pragma GCC diagnostic ignored "-Wcast-align" 238 uint16_t *ptr_w = (uint16_t *)ptr_b;
239 #pragma GCC diagnostic pop 247 ptr_b=(uint8_t *)ptr_w;
257 #pragma GCC diagnostic push 258 #pragma GCC diagnostic ignored "-Wcast-align" 259 uint16_t b_data = *((uint16_t *)&eeprom_buffer[i]);
260 #pragma GCC diagnostic pop 269 #if defined(WRITE_IN_THREAD) 275 uint16_t new_wp =
wr_ptr+1;
293 #if defined(WRITE_IN_THREAD)
bool get_soft_armed() const
static void do_on_disarm()
static Handler get_handler(AP_HAL::MemberProc proc)
static uint8_t _read_byte(uint16_t loc)
void read_block(void *dst, uint16_t src, size_t n)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define BOARD_STORAGE_SIZE
void write_block(uint16_t dst, const void *src, size_t n)
static void set_task_priority(void *h, uint8_t prio)
static void _write_byte(uint16_t loc, uint8_t value)
static volatile uint16_t rd_ptr
static void register_on_disarm(Handler h)
static void error_parse(uint16_t status)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void set_task_active(void *h)
static uint8_t read_byte(uint16_t loc)
Storage::Item Storage::queue [EEPROM_QUEUE_LEN] IN_CCM
static void write_thread()
static Item queue[EEPROM_QUEUE_LEN]
static void write_byte(uint16_t loc, uint8_t value)
static volatile uint16_t wr_ptr
void panic(const char *errormsg,...) FMT_PRINTF(1
static bool write_deferred
static void late_init(bool defer)
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
void hal_yield(uint16_t ttw)
static void write_word(uint16_t loc, uint16_t value)