From 84c39774fa94990eb9d1268ca6d85110564db656 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Aug 2012 16:27:19 +1000 Subject: [PATCH] DataFlash: fixed SITL build --- libraries/DataFlash/DataFlash.cpp | 2 +- libraries/DataFlash/DataFlash.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/DataFlash/DataFlash.cpp b/libraries/DataFlash/DataFlash.cpp index 5e490b5734..f7372d4cb0 100644 --- a/libraries/DataFlash/DataFlash.cpp +++ b/libraries/DataFlash/DataFlash.cpp @@ -273,7 +273,7 @@ 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, 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 look; diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index 3138471619..a55caebe5d 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -84,7 +84,7 @@ class DataFlash_Class // high level interface 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); void start_new_log(void);