mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 08:44:08 -04:00
AP_HAL_SITL: correct compilation for mission pread/pwrite ret check
This commit is contained in:
parent
9a1a748348
commit
d9e3526bd2
@ -232,7 +232,9 @@ static void sitl_flash_open(void)
|
|||||||
}
|
}
|
||||||
uint8_t fill[HAL_FLASH_SECTOR_SIZE*2];
|
uint8_t fill[HAL_FLASH_SECTOR_SIZE*2];
|
||||||
memset(fill, 0xff, sizeof(fill));
|
memset(fill, 0xff, sizeof(fill));
|
||||||
pwrite(flash_fd, fill, sizeof(fill), 0);
|
if (pwrite(flash_fd, fill, sizeof(fill), 0) != (ssize_t)sizeof(fill)) {
|
||||||
|
AP_HAL::panic("Failed to fill flash.dat");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -241,7 +243,7 @@ static bool sitl_flash_write(uint32_t addr, const uint8_t *data, uint32_t length
|
|||||||
{
|
{
|
||||||
sitl_flash_open();
|
sitl_flash_open();
|
||||||
uint8_t old[length];
|
uint8_t old[length];
|
||||||
if (pread(flash_fd, old, length, addr) != length) {
|
if (pread(flash_fd, old, length, addr) != (ssize_t)length) {
|
||||||
AP_HAL::panic("Failed to read flash.dat at %u len=%u", unsigned(addr), unsigned(length));
|
AP_HAL::panic("Failed to read flash.dat at %u len=%u", unsigned(addr), unsigned(length));
|
||||||
}
|
}
|
||||||
#if defined(HAL_FLASH_MIN_WRITE_SIZE) && HAL_FLASH_MIN_WRITE_SIZE == 32
|
#if defined(HAL_FLASH_MIN_WRITE_SIZE) && HAL_FLASH_MIN_WRITE_SIZE == 32
|
||||||
@ -275,13 +277,13 @@ static bool sitl_flash_write(uint32_t addr, const uint8_t *data, uint32_t length
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
return pwrite(flash_fd, data, length, addr) == length;
|
return pwrite(flash_fd, data, length, addr) == (ssize_t)length;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool sitl_flash_read(uint32_t addr, uint8_t *data, uint32_t length)
|
static bool sitl_flash_read(uint32_t addr, uint8_t *data, uint32_t length)
|
||||||
{
|
{
|
||||||
sitl_flash_open();
|
sitl_flash_open();
|
||||||
return pread(flash_fd, data, length, addr) == length;
|
return pread(flash_fd, data, length, addr) == (ssize_t)length;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool sitl_flash_erasepage(uint32_t page)
|
static bool sitl_flash_erasepage(uint32_t page)
|
||||||
|
Loading…
Reference in New Issue
Block a user