mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
DataFlash: change "unsigned long" to "uint32_t" in callback functions
This commit is contained in:
parent
221e4ea32a
commit
ba48bffb46
@ -187,7 +187,7 @@ uint16_t DataFlash_Class::GetFilePage()
|
||||
return df_FilePage;
|
||||
}
|
||||
|
||||
void DataFlash_Class::EraseAll(void (*delay_cb)(unsigned long))
|
||||
void DataFlash_Class::EraseAll(void (*delay_cb)(uint32_t))
|
||||
{
|
||||
for(uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
|
||||
BlockErase(j);
|
||||
@ -344,12 +344,12 @@ int16_t DataFlash_Class::find_last_page(void)
|
||||
uint32_t top_hash;
|
||||
|
||||
StartRead(bottom);
|
||||
bottom_hash = ((long)GetFileNumber()<<16) | GetFilePage();
|
||||
bottom_hash = ((int32_t)GetFileNumber()<<16) | GetFilePage();
|
||||
|
||||
while(top-bottom > 1) {
|
||||
look = (top+bottom)/2;
|
||||
StartRead(look);
|
||||
look_hash = (long)GetFileNumber()<<16 | GetFilePage();
|
||||
look_hash = (int32_t)GetFileNumber()<<16 | GetFilePage();
|
||||
if (look_hash >= 0xFFFF0000) look_hash = 0;
|
||||
|
||||
if(look_hash < bottom_hash) {
|
||||
@ -363,7 +363,7 @@ int16_t DataFlash_Class::find_last_page(void)
|
||||
}
|
||||
|
||||
StartRead(top);
|
||||
top_hash = ((long)GetFileNumber()<<16) | GetFilePage();
|
||||
top_hash = ((int32_t)GetFileNumber()<<16) | GetFilePage();
|
||||
if (top_hash >= 0xFFFF0000) {
|
||||
top_hash = 0;
|
||||
}
|
||||
@ -400,13 +400,13 @@ int16_t DataFlash_Class::find_last_page_of_log(uint16_t log_number)
|
||||
top = find_last_page();
|
||||
}
|
||||
|
||||
check_hash = (long)log_number<<16 | 0xFFFF;
|
||||
check_hash = (int32_t)log_number<<16 | 0xFFFF;
|
||||
|
||||
while(top-bottom > 1)
|
||||
{
|
||||
look = (top+bottom)/2;
|
||||
StartRead(look);
|
||||
look_hash = (long)GetFileNumber()<<16 | GetFilePage();
|
||||
look_hash = (int32_t)GetFileNumber()<<16 | GetFilePage();
|
||||
if (look_hash >= 0xFFFF0000) look_hash = 0;
|
||||
|
||||
if(look_hash > check_hash) {
|
||||
|
@ -58,7 +58,7 @@ class DataFlash_Class
|
||||
int16_t GetWritePage(void);
|
||||
|
||||
// erase handling
|
||||
void EraseAll(void (*delay_cb)(unsigned long));
|
||||
void EraseAll(void (*delay_cb)(uint32_t));
|
||||
bool NeedErase(void);
|
||||
|
||||
// Write methods
|
||||
|
@ -317,7 +317,7 @@ void DataFlash_APM1::BlockErase (uint16_t BlockAdr)
|
||||
|
||||
|
||||
|
||||
void DataFlash_APM1::ChipErase(void (*delay_cb)(unsigned long))
|
||||
void DataFlash_APM1::ChipErase(void (*delay_cb)(uint32_t))
|
||||
{
|
||||
|
||||
dataflash_CS_active(); // activate dataflash command decoder
|
||||
|
@ -20,7 +20,7 @@ class DataFlash_APM1 : public DataFlash_Class
|
||||
uint16_t PageSize();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void BlockErase (uint16_t BlockAdr);
|
||||
void ChipErase(void (*delay_cb)(unsigned long));
|
||||
void ChipErase(void (*delay_cb)(uint32_t));
|
||||
|
||||
public:
|
||||
|
||||
|
@ -394,7 +394,7 @@ void DataFlash_APM2::BlockErase(uint16_t BlockAdr)
|
||||
}
|
||||
|
||||
|
||||
void DataFlash_APM2::ChipErase(void (*delay_cb)(unsigned long))
|
||||
void DataFlash_APM2::ChipErase(void (*delay_cb)(uint32_t))
|
||||
{
|
||||
//serialDebug("Chip Erase\n");
|
||||
|
||||
|
@ -24,7 +24,7 @@ class DataFlash_APM2 : public DataFlash_Class
|
||||
void CS_active();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void BlockErase (uint16_t BlockAdr);
|
||||
void ChipErase(void (*delay_cb)(unsigned long));
|
||||
void ChipErase(void (*delay_cb)(uint32_t));
|
||||
|
||||
public:
|
||||
DataFlash_APM2(); // Constructor
|
||||
|
Loading…
Reference in New Issue
Block a user