Browse Source

Plane: use hal.storage for eeprom access

master
Andrew Tridgell 12 years ago
parent
commit
7c6dd0736e
  1. 26
      ArduPlane/commands.pde
  2. 12
      ArduPlane/geofence.pde
  3. 4
      ArduPlane/setup.pde
  4. 4
      ArduPlane/test.pde

26
ArduPlane/commands.pde

@ -55,22 +55,22 @@ static struct Location get_cmd_with_index_raw(int16_t i) @@ -55,22 +55,22 @@ static struct Location get_cmd_with_index_raw(int16_t i)
}else{
// read WP position
mem = (WP_START_BYTE) + (i * WP_SIZE);
temp.id = eeprom_read_byte((uint8_t*)(uintptr_t)mem);
temp.id = hal.storage->read_byte(mem);
mem++;
temp.options = eeprom_read_byte((uint8_t*)(uintptr_t)mem);
temp.options = hal.storage->read_byte(mem);
mem++;
temp.p1 = eeprom_read_byte((uint8_t*)(uintptr_t)mem);
temp.p1 = hal.storage->read_byte(mem);
mem++;
temp.alt = (long)eeprom_read_dword((uint32_t*)(uintptr_t)mem);
temp.alt = hal.storage->read_dword(mem);
mem += 4;
temp.lat = (long)eeprom_read_dword((uint32_t*)(uintptr_t)mem);
temp.lat = hal.storage->read_dword(mem);
mem += 4;
temp.lng = (long)eeprom_read_dword((uint32_t*)(uintptr_t)mem);
temp.lng = hal.storage->read_dword(mem);
}
return temp;
@ -100,7 +100,7 @@ static struct Location get_cmd_with_index(int16_t i) @@ -100,7 +100,7 @@ static struct Location get_cmd_with_index(int16_t i)
static void set_cmd_with_index(struct Location temp, int16_t i)
{
i = constrain(i, 0, g.command_total.get());
intptr_t mem = WP_START_BYTE + (i * WP_SIZE);
uint16_t mem = WP_START_BYTE + (i * WP_SIZE);
// Set altitude options bitmask
// XXX What is this trying to do?
@ -110,22 +110,22 @@ static void set_cmd_with_index(struct Location temp, int16_t i) @@ -110,22 +110,22 @@ static void set_cmd_with_index(struct Location temp, int16_t i)
temp.options = 0;
}
eeprom_write_byte((uint8_t *) mem, temp.id);
hal.storage->write_byte(mem, temp.id);
mem++;
eeprom_write_byte((uint8_t *) mem, temp.options);
hal.storage->write_byte(mem, temp.options);
mem++;
eeprom_write_byte((uint8_t *) mem, temp.p1);
hal.storage->write_byte(mem, temp.p1);
mem++;
eeprom_write_dword((uint32_t *) mem, temp.alt);
hal.storage->write_dword(mem, temp.alt);
mem += 4;
eeprom_write_dword((uint32_t *) mem, temp.lat);
hal.storage->write_dword(mem, temp.lat);
mem += 4;
eeprom_write_dword((uint32_t *) mem, temp.lng);
hal.storage->write_dword(mem, temp.lng);
}
static void decrement_cmd_index()

12
ArduPlane/geofence.pde

@ -33,7 +33,7 @@ static struct geofence_state { @@ -33,7 +33,7 @@ static struct geofence_state {
*/
static Vector2l get_fence_point_with_index(unsigned i)
{
intptr_t mem;
uint16_t mem;
Vector2l ret;
if (i > (unsigned)g.fence_total) {
@ -42,9 +42,9 @@ static Vector2l get_fence_point_with_index(unsigned i) @@ -42,9 +42,9 @@ static Vector2l get_fence_point_with_index(unsigned i)
// read fence point
mem = FENCE_START_BYTE + (i * FENCE_WP_SIZE);
ret.x = eeprom_read_dword((uint32_t *)mem);
ret.x = hal.storage->read_dword(mem);
mem += sizeof(uint32_t);
ret.y = eeprom_read_dword((uint32_t *)mem);
ret.y = hal.storage->read_dword(mem);
return ret;
}
@ -52,7 +52,7 @@ static Vector2l get_fence_point_with_index(unsigned i) @@ -52,7 +52,7 @@ static Vector2l get_fence_point_with_index(unsigned i)
// save a fence point
static void set_fence_point_with_index(Vector2l &point, unsigned i)
{
intptr_t mem;
uint16_t mem;
if (i >= (unsigned)g.fence_total.get()) {
// not allowed
@ -61,9 +61,9 @@ static void set_fence_point_with_index(Vector2l &point, unsigned i) @@ -61,9 +61,9 @@ static void set_fence_point_with_index(Vector2l &point, unsigned i)
mem = FENCE_START_BYTE + (i * FENCE_WP_SIZE);
eeprom_write_dword((uint32_t *)mem, point.x);
hal.storage->write_dword(mem, point.x);
mem += sizeof(uint32_t);
eeprom_write_dword((uint32_t *)mem, point.y);
hal.storage->write_dword(mem, point.y);
if (geofence_state != NULL) {
geofence_state->boundary_uptodate = false;

4
ArduPlane/setup.pde

@ -607,8 +607,8 @@ static void zero_eeprom(void) @@ -607,8 +607,8 @@ static void zero_eeprom(void)
{
uint8_t b = 0;
cliSerial->printf_P(PSTR("\nErasing EEPROM\n"));
for (intptr_t i = 0; i < EEPROM_MAX_ADDR; i++) {
eeprom_write_byte((uint8_t *) i, b);
for (uint16_t i = 0; i < EEPROM_MAX_ADDR; i++) {
hal.storage->write_byte(i, b);
}
cliSerial->printf_P(PSTR("done\n"));
}

4
ArduPlane/test.pde

@ -82,13 +82,13 @@ static void print_hit_enter() @@ -82,13 +82,13 @@ static void print_hit_enter()
static int8_t
test_eedump(uint8_t argc, const Menu::arg *argv)
{
intptr_t i, j;
uint16_t i, j;
// hexdump the EEPROM
for (i = 0; i < EEPROM_MAX_ADDR; i += 16) {
cliSerial->printf_P(PSTR("%04x:"), i);
for (j = 0; j < 16; j++)
cliSerial->printf_P(PSTR(" %02x"), eeprom_read_byte((const uint8_t *)(i + j)));
cliSerial->printf_P(PSTR(" %02x"), hal.storage->read_byte(i + j));
cliSerial->println();
}
return(0);

Loading…
Cancel
Save