APM:Libraries
|
#include <StorageManager.h>
Public Member Functions | |
StorageAccess (StorageManager::StorageType _type) | |
uint16_t | size (void) const |
bool | read_block (void *dst, uint16_t src, size_t n) const |
bool | write_block (uint16_t dst, const void *src, size_t n) const |
uint8_t | read_byte (uint16_t loc) const |
uint16_t | read_uint16 (uint16_t loc) const |
uint32_t | read_uint32 (uint16_t loc) const |
void | write_byte (uint16_t loc, uint8_t value) const |
void | write_uint16 (uint16_t loc, uint16_t value) const |
void | write_uint32 (uint16_t loc, uint32_t value) const |
Private Attributes | |
const StorageManager::StorageType | type |
uint16_t | total_size |
Definition at line 76 of file StorageManager.h.
StorageAccess::StorageAccess | ( | StorageManager::StorageType | _type | ) |
Definition at line 114 of file StorageManager.cpp.
bool StorageAccess::read_block | ( | void * | dst, |
uint16_t | src, | ||
size_t | n | ||
) | const |
Definition at line 131 of file StorageManager.cpp.
Referenced by AP_Param::find_old_parameter(), AP_Rally::get_rally_point_with_index(), AP_Param::load(), AP_Param::load_all(), AP_Param::load_object_from_eeprom(), loop(), read_byte(), AP_Mission::read_cmd_from_storage(), read_uint16(), read_uint32(), AP_Param::scan(), and AP_Param::setup().
uint8_t StorageAccess::read_byte | ( | uint16_t | loc | ) | const |
Definition at line 209 of file StorageManager.cpp.
Referenced by AP_Mission::read_cmd_from_storage().
uint16_t StorageAccess::read_uint16 | ( | uint16_t | loc | ) | const |
Definition at line 219 of file StorageManager.cpp.
Referenced by AP_Mission::read_cmd_from_storage().
uint32_t StorageAccess::read_uint32 | ( | uint16_t | loc | ) | const |
Definition at line 229 of file StorageManager.cpp.
Referenced by AP_Mission::check_eeprom_version(), and AC_PolyFence_loader::load_point_from_eeprom().
|
inline |
Definition at line 82 of file StorageManager.h.
Referenced by AP_Param::load_all(), AP_Param::load_object_from_eeprom(), loop(), AC_PolyFence_loader::max_points(), AP_Mission::num_commands_max(), AP_Param::save(), AP_Param::scan(), and setup().
bool StorageAccess::write_block | ( | uint16_t | dst, |
const void * | src, | ||
size_t | n | ||
) | const |
Definition at line 171 of file StorageManager.cpp.
Referenced by AP_Param::eeprom_write_check(), loop(), AP_Rally::set_rally_point_with_index(), write_byte(), AP_Mission::write_cmd_to_storage(), write_uint16(), and write_uint32().
void StorageAccess::write_byte | ( | uint16_t | loc, |
uint8_t | value | ||
) | const |
Definition at line 239 of file StorageManager.cpp.
Referenced by setup(), and AP_Mission::write_cmd_to_storage().
void StorageAccess::write_uint16 | ( | uint16_t | loc, |
uint16_t | value | ||
) | const |
Definition at line 247 of file StorageManager.cpp.
Referenced by AP_Mission::write_cmd_to_storage().
void StorageAccess::write_uint32 | ( | uint16_t | loc, |
uint32_t | value | ||
) | const |
Definition at line 255 of file StorageManager.cpp.
Referenced by AP_Mission::check_eeprom_version(), and AC_PolyFence_loader::save_point_to_eeprom().
|
private |
Definition at line 99 of file StorageManager.h.
Referenced by StorageAccess().
|
private |
Definition at line 98 of file StorageManager.h.
Referenced by read_block(), StorageAccess(), and write_block().