mirror of https://github.com/ArduPilot/ardupilot
DataFlash: fixed SITL build
This commit is contained in:
parent
2fb8a13ac6
commit
84c39774fa
|
@ -273,7 +273,7 @@ void DataFlash_Class::start_new_log(void)
|
||||||
|
|
||||||
// This function finds the first and last pages of a log file
|
// 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.
|
// 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, int & start_page, int & end_page)
|
void DataFlash_Class::get_log_boundaries(uint8_t log_num, int16_t & start_page, int16_t & end_page)
|
||||||
{
|
{
|
||||||
int num = get_num_logs();
|
int num = get_num_logs();
|
||||||
int look;
|
int look;
|
||||||
|
|
|
@ -84,7 +84,7 @@ class DataFlash_Class
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
int find_last_log(void);
|
int find_last_log(void);
|
||||||
void get_log_boundaries(uint8_t log_num, int & start_page, int & end_page);
|
void get_log_boundaries(uint8_t log_num, int16_t & start_page, int16_t & end_page);
|
||||||
uint8_t get_num_logs(void);
|
uint8_t get_num_logs(void);
|
||||||
void start_new_log(void);
|
void start_new_log(void);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue