mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
DataFlash: added log_num to dump interface
this will be used by the file oriented logging code
This commit is contained in:
parent
c52ef80f06
commit
7b524d15fa
@ -39,8 +39,9 @@ public:
|
|||||||
virtual void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
virtual void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
||||||
virtual uint8_t get_num_logs(void) = 0;
|
virtual uint8_t get_num_logs(void) = 0;
|
||||||
virtual void start_new_log(void) = 0;
|
virtual void start_new_log(void) = 0;
|
||||||
virtual uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
|
virtual uint16_t log_read_process(uint8_t log_num,
|
||||||
void (*callback)(uint8_t msgid)) = 0;
|
uint16_t start_page, uint16_t end_page,
|
||||||
|
void (*callback)(uint8_t msgid)) = 0;
|
||||||
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
|
|
||||||
|
@ -40,7 +40,8 @@ public:
|
|||||||
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page);
|
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_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);
|
||||||
uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
|
uint16_t log_read_process(uint8_t log_num,
|
||||||
|
uint16_t start_page, uint16_t end_page,
|
||||||
void (*callback)(uint8_t msgid));
|
void (*callback)(uint8_t msgid));
|
||||||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
|
@ -234,8 +234,11 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
|||||||
Read the DataFlash log memory
|
Read the DataFlash log memory
|
||||||
Call the callback() function on each log message found in the page
|
Call the callback() function on each log message found in the page
|
||||||
range. Return the number of log messages found
|
range. Return the number of log messages found
|
||||||
|
|
||||||
|
Note that for the block oriented backend the log_num is ignored
|
||||||
*/
|
*/
|
||||||
uint16_t DataFlash_Block::log_read_process(uint16_t start_page, uint16_t end_page,
|
uint16_t DataFlash_Block::log_read_process(uint8_t log_num,
|
||||||
|
uint16_t start_page, uint16_t end_page,
|
||||||
void (*callback)(uint8_t msgid))
|
void (*callback)(uint8_t msgid))
|
||||||
{
|
{
|
||||||
uint8_t log_step = 0;
|
uint8_t log_step = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user