mirror of https://github.com/ArduPilot/ardupilot
DataFlash: remove DATAFLASH_NO_CLI
This is not used anymore since the removal of AVR CPUs.
This commit is contained in:
parent
c55c07eaf6
commit
c74b1a660d
|
@ -68,7 +68,6 @@ void DataFlash_Class::Log_Fill_Format(const struct LogStructure *s, struct log_F
|
|||
backend->Log_Fill_Format(s, pkt);
|
||||
}
|
||||
|
||||
#ifndef DATAFLASH_NO_CLI
|
||||
void DataFlash_Class::LogReadProcess(uint16_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
print_mode_fn printMode,
|
||||
|
@ -84,7 +83,6 @@ void DataFlash_Class::ShowDeviceInfo(AP_HAL::BetterStream *port) {
|
|||
void DataFlash_Class::ListAvailableLogs(AP_HAL::BetterStream *port) {
|
||||
backend->ListAvailableLogs(port);
|
||||
}
|
||||
#endif // DATAFLASH_NO_CLI
|
||||
|
||||
bool DataFlash_Class::logging_started(void) {
|
||||
return backend->log_write_started;
|
||||
|
|
|
@ -68,7 +68,6 @@ public:
|
|||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||
uint16_t get_num_logs(void);
|
||||
#ifndef DATAFLASH_NO_CLI
|
||||
void LogReadProcess(uint16_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
print_mode_fn printMode,
|
||||
|
@ -76,7 +75,6 @@ public:
|
|||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||
#endif // DATAFLASH_NO_CLI
|
||||
|
||||
uint16_t bufferspace_available();
|
||||
|
||||
|
|
|
@ -44,7 +44,6 @@ public:
|
|||
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
|
||||
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
|
||||
virtual uint16_t get_num_logs() = 0;
|
||||
#ifndef DATAFLASH_NO_CLI
|
||||
virtual void LogReadProcess(const uint16_t list_entry,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
print_mode_fn printMode,
|
||||
|
@ -52,7 +51,6 @@ public:
|
|||
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
||||
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
||||
virtual void ListAvailableLogs(AP_HAL::BetterStream *port) = 0;
|
||||
#endif // DATAFLASH_NO_CLI
|
||||
|
||||
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
||||
bool logging_started(void) const { return log_write_started; }
|
||||
|
|
|
@ -38,7 +38,6 @@ public:
|
|||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||
uint16_t get_num_logs() override;
|
||||
uint16_t start_new_log(void);
|
||||
#ifndef DATAFLASH_NO_CLI
|
||||
void LogReadProcess(const uint16_t list_entry,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
print_mode_fn print_mode,
|
||||
|
@ -46,7 +45,6 @@ public:
|
|||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||
#endif
|
||||
|
||||
uint16_t bufferspace_available();
|
||||
|
||||
|
|
|
@ -290,7 +290,6 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
|||
|
||||
#define PGM_UINT8(addr) pgm_read_byte((const char *)addr)
|
||||
|
||||
#ifndef DATAFLASH_NO_CLI
|
||||
/*
|
||||
read and print a log entry using the format strings from the given structure
|
||||
- this really should in in the frontend, not the backend
|
||||
|
@ -601,7 +600,6 @@ void DataFlash_Block::ListAvailableLogs(AP_HAL::BetterStream *port)
|
|||
}
|
||||
port->println();
|
||||
}
|
||||
#endif // DATAFLASH_NO_CLI
|
||||
|
||||
// This function starts a new log file in the DataFlash, and writes
|
||||
// the format of supported messages in the log
|
||||
|
|
Loading…
Reference in New Issue