mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Log: make find_last_log_page() portable
this makes it work with platforms with a larger 'long'
This commit is contained in:
parent
acad6b37c4
commit
4113d04f70
@ -338,7 +338,7 @@ static int find_last_log_page(int bottom_page)
|
||||
{
|
||||
int top_page = 4096;
|
||||
int look_page;
|
||||
long check;
|
||||
int32_t check;
|
||||
|
||||
while((top_page - bottom_page) > 1) {
|
||||
look_page = (top_page + bottom_page) / 2;
|
||||
@ -347,7 +347,7 @@ static int find_last_log_page(int bottom_page)
|
||||
|
||||
//Serial.printf("look page:%d, check:%d\n", look_page, check);
|
||||
|
||||
if(check == (long)0xFFFFFFFF)
|
||||
if(check == (int32_t)~0)
|
||||
top_page = look_page;
|
||||
else
|
||||
bottom_page = look_page;
|
||||
|
@ -313,13 +313,13 @@ static int find_last_log_page(int bottom_page)
|
||||
{
|
||||
int top_page = 4096;
|
||||
int look_page;
|
||||
long check;
|
||||
int32_t check;
|
||||
|
||||
while((top_page - bottom_page) > 1) {
|
||||
look_page = (top_page + bottom_page) / 2;
|
||||
DataFlash.StartRead(look_page);
|
||||
check = DataFlash.ReadLong();
|
||||
if(check == (long)0xFFFFFFFF)
|
||||
if(check == (int32_t)~0)
|
||||
top_page = look_page;
|
||||
else
|
||||
bottom_page = look_page;
|
||||
|
Loading…
Reference in New Issue
Block a user