From 73d70354a3e50223ececbcdd4f3af16e3db3e97f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 9 Aug 2012 16:18:53 +1000 Subject: [PATCH] AP_Param: fixed some build warnings --- libraries/AP_Common/AP_Param.cpp | 8 ++++---- libraries/AP_Common/AP_Param.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Common/AP_Param.cpp b/libraries/AP_Common/AP_Param.cpp index 250bf08ad2..c1b449f340 100644 --- a/libraries/AP_Common/AP_Param.cpp +++ b/libraries/AP_Common/AP_Param.cpp @@ -71,9 +71,9 @@ void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size) { const uint8_t *b = (const uint8_t *)ptr; while (size--) { - uint8_t v = eeprom_read_byte((const uint8_t *)ofs); + uint8_t v = eeprom_read_byte((const uint8_t *)(uintptr_t)ofs); if (v != *b) { - eeprom_write_byte((uint8_t *)ofs, *b); + eeprom_write_byte((uint8_t *)(uintptr_t)ofs, *b); } b++; ofs++; @@ -432,7 +432,7 @@ bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs) struct Param_header phdr; uint16_t ofs = sizeof(AP_Param::EEPROM_header); while (ofs < _eeprom_size) { - eeprom_read_block(&phdr, (void *)ofs, sizeof(phdr)); + eeprom_read_block(&phdr, (void *)(uintptr_t)ofs, sizeof(phdr)); if (phdr.type == target->type && phdr.key == target->key && phdr.group_element == target->group_element) { @@ -775,7 +775,7 @@ bool AP_Param::load_all(void) uint16_t ofs = sizeof(AP_Param::EEPROM_header); while (ofs < _eeprom_size) { - eeprom_read_block(&phdr, (void *)ofs, sizeof(phdr)); + eeprom_read_block(&phdr, (void *)(uintptr_t)ofs, sizeof(phdr)); // note that this is an || not an && for robustness // against power off while adding a variable if (phdr.type == _sentinal_type || diff --git a/libraries/AP_Common/AP_Param.h b/libraries/AP_Common/AP_Param.h index 585982fad2..9623adf11e 100644 --- a/libraries/AP_Common/AP_Param.h +++ b/libraries/AP_Common/AP_Param.h @@ -221,7 +221,7 @@ private: static const uint8_t _group_bits = 18; static const uint8_t _sentinal_key = 0xFF; - static const uint8_t _sentinal_type = 0xFF; + static const uint8_t _sentinal_type = 0x3F; static const uint8_t _sentinal_group = 0xFF; static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits);