From a3c3c59b82768b0bd8dac6875c0f474a8f09d7cb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 Nov 2012 08:27:51 +1100 Subject: [PATCH] ACM: fixed some memory cast warnings --- ArduCopter/commands.pde | 4 ++-- ArduCopter/setup.pde | 2 +- ArduCopter/test.pde | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 1c769e8b96..b3ac35d65d 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -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); diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index d3393caaf2..213520e4ca 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -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); } diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index bb359fe6f7..1f94de5e2c 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -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) {