mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
DataFlash: fixed signed/unsigned errors in API
This commit is contained in:
parent
9b551f162c
commit
0ffcffa81c
@ -9,7 +9,7 @@
|
||||
extern AP_HAL::HAL& hal;
|
||||
|
||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||
void DataFlash_Class::StartWrite(int16_t PageAdr)
|
||||
void DataFlash_Class::StartWrite(uint16_t PageAdr)
|
||||
{
|
||||
df_BufferIdx = 0;
|
||||
df_BufferNum = 0;
|
||||
@ -65,18 +65,18 @@ void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size)
|
||||
|
||||
|
||||
// Get the last page written to
|
||||
int16_t DataFlash_Class::GetWritePage()
|
||||
uint16_t DataFlash_Class::GetWritePage()
|
||||
{
|
||||
return df_PageAdr;
|
||||
}
|
||||
|
||||
// Get the last page read
|
||||
int16_t DataFlash_Class::GetPage()
|
||||
uint16_t DataFlash_Class::GetPage()
|
||||
{
|
||||
return df_Read_PageAdr;
|
||||
}
|
||||
|
||||
void DataFlash_Class::StartRead(int16_t PageAdr)
|
||||
void DataFlash_Class::StartRead(uint16_t PageAdr)
|
||||
{
|
||||
df_Read_BufferNum = 0;
|
||||
df_Read_PageAdr = PageAdr;
|
||||
|
@ -35,8 +35,8 @@ public:
|
||||
void ReadPacket(void *pkt, uint16_t size);
|
||||
|
||||
// high level interface
|
||||
int16_t find_last_log(void);
|
||||
void get_log_boundaries(uint8_t log_num, int16_t & start_page, int16_t & end_page);
|
||||
uint16_t find_last_log(void);
|
||||
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||
uint8_t get_num_logs(void);
|
||||
void start_new_log(void);
|
||||
uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
|
||||
@ -87,15 +87,15 @@ private:
|
||||
virtual bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) = 0;
|
||||
|
||||
// start reading at the given page
|
||||
void StartRead(int16_t PageAdr);
|
||||
void StartRead(uint16_t PageAdr);
|
||||
|
||||
// internal high level functions
|
||||
int16_t find_last_page(void);
|
||||
int16_t find_last_page_of_log(uint16_t log_number);
|
||||
uint16_t find_last_page(void);
|
||||
uint16_t find_last_page_of_log(uint16_t log_number);
|
||||
bool check_wrapped(void);
|
||||
int16_t GetPage(void);
|
||||
int16_t GetWritePage(void);
|
||||
void StartWrite(int16_t PageAdr);
|
||||
uint16_t GetPage(void);
|
||||
uint16_t GetWritePage(void);
|
||||
void StartWrite(uint16_t PageAdr);
|
||||
void FinishWrite(void);
|
||||
|
||||
// Read methods
|
||||
|
@ -17,7 +17,7 @@ uint8_t DataFlash_Class::get_num_logs(void)
|
||||
|
||||
StartRead(1);
|
||||
|
||||
if (GetFileNumber() == 0XFFFF) {
|
||||
if (GetFileNumber() == 0xFFFF) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -71,15 +71,15 @@ void DataFlash_Class::start_new_log(void)
|
||||
|
||||
// This function finds the first and last pages of a log file
|
||||
// The first page may be greater than the last page if the DataFlash has been filled and partially overwritten.
|
||||
void DataFlash_Class::get_log_boundaries(uint8_t log_num, int16_t & start_page, int16_t & end_page)
|
||||
void DataFlash_Class::get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page)
|
||||
{
|
||||
int16_t num = get_num_logs();
|
||||
int16_t look;
|
||||
uint16_t num = get_num_logs();
|
||||
uint16_t look;
|
||||
|
||||
if(num == 1)
|
||||
{
|
||||
StartRead(df_NumPages);
|
||||
if(GetFileNumber() == 0xFFFF)
|
||||
if (GetFileNumber() == 0xFFFF)
|
||||
{
|
||||
start_page = 1;
|
||||
end_page = find_last_page_of_log((uint16_t)log_num);
|
||||
@ -108,9 +108,13 @@ void DataFlash_Class::get_log_boundaries(uint8_t log_num, int16_t & start_page,
|
||||
}
|
||||
}
|
||||
}
|
||||
if(start_page == (int16_t)df_NumPages+1 || start_page == 0) start_page=1;
|
||||
end_page = find_last_page_of_log((uint16_t)log_num);
|
||||
if(end_page <= 0) end_page = start_page;
|
||||
if (start_page == df_NumPages+1 || start_page == 0) {
|
||||
start_page = 1;
|
||||
}
|
||||
end_page = find_last_page_of_log(log_num);
|
||||
if (end_page == 0) {
|
||||
end_page = start_page;
|
||||
}
|
||||
}
|
||||
|
||||
bool DataFlash_Class::check_wrapped(void)
|
||||
@ -124,15 +128,15 @@ bool DataFlash_Class::check_wrapped(void)
|
||||
|
||||
|
||||
// This funciton finds the last log number
|
||||
int16_t DataFlash_Class::find_last_log(void)
|
||||
uint16_t DataFlash_Class::find_last_log(void)
|
||||
{
|
||||
int16_t last_page = find_last_page();
|
||||
uint16_t last_page = find_last_page();
|
||||
StartRead(last_page);
|
||||
return GetFileNumber();
|
||||
}
|
||||
|
||||
// This function finds the last page of the last file
|
||||
int16_t DataFlash_Class::find_last_page(void)
|
||||
uint16_t DataFlash_Class::find_last_page(void)
|
||||
{
|
||||
uint16_t look;
|
||||
uint16_t bottom = 1;
|
||||
@ -173,7 +177,7 @@ int16_t DataFlash_Class::find_last_page(void)
|
||||
}
|
||||
|
||||
// This function finds the last page of a particular log file
|
||||
int16_t DataFlash_Class::find_last_page_of_log(uint16_t log_number)
|
||||
uint16_t DataFlash_Class::find_last_page_of_log(uint16_t log_number)
|
||||
{
|
||||
uint16_t look;
|
||||
uint16_t bottom;
|
||||
|
Loading…
Reference in New Issue
Block a user