ACM: fixed some memory cast warnings

This commit is contained in:
Andrew Tridgell 2012-11-19 08:27:51 +11:00
parent 8311062610
commit a3c3c59b82
3 changed files with 4 additions and 4 deletions

View File

@ -35,7 +35,7 @@ static struct Location get_cmd_with_index(int i)
}else{
// we can load a command, we don't process it yet
// read WP position
int32_t mem = (WP_START_BYTE) + (i * WP_SIZE);
uintptr_t mem = (WP_START_BYTE) + (i * WP_SIZE);
temp.id = eeprom_read_byte((uint8_t*)mem);
@ -84,7 +84,7 @@ static void set_cmd_with_index(struct Location temp, int i)
temp.id = MAV_CMD_NAV_WAYPOINT;
}
uint32_t mem = WP_START_BYTE + (i * WP_SIZE);
uintptr_t mem = WP_START_BYTE + (i * WP_SIZE);
eeprom_write_byte((uint8_t *) mem, temp.id);

View File

@ -961,7 +961,7 @@ static void zero_eeprom(void)
Serial.printf_P(PSTR("\nErasing EEPROM\n"));
for (int16_t i = 0; i < EEPROM_MAX_ADDR; i++) {
for (uintptr_t i = 0; i < EEPROM_MAX_ADDR; i++) {
eeprom_write_byte((uint8_t *) i, b);
}

View File

@ -104,7 +104,7 @@ test_mode(uint8_t argc, const Menu::arg *argv)
static int8_t
test_eedump(uint8_t argc, const Menu::arg *argv)
{
int i, j;
uintptr_t i, j;
// hexdump the EEPROM
for (i = 0; i < EEPROM_MAX_ADDR; i += 16) {