mirror of https://github.com/ArduPilot/ardupilot
DataFlash: use override keyword on many methods
This commit is contained in:
parent
65bd77cc67
commit
d8c475ad04
|
@ -33,43 +33,43 @@ public:
|
|||
|
||||
// initialisation
|
||||
void Init() override;
|
||||
bool CardInserted(void);
|
||||
bool CardInserted(void) override;
|
||||
|
||||
// erase handling
|
||||
void EraseAll();
|
||||
void EraseAll() override;
|
||||
|
||||
// possibly time-consuming preparation handling:
|
||||
bool NeedPrep();
|
||||
void Prep();
|
||||
bool NeedPrep() override;
|
||||
void Prep() override;
|
||||
|
||||
/* Write a block of data at current offset */
|
||||
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
|
||||
uint32_t bufferspace_available();
|
||||
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) override;
|
||||
uint32_t bufferspace_available() override;
|
||||
|
||||
// high level interface
|
||||
uint16_t find_last_log() override;
|
||||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||
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);
|
||||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) override;
|
||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
|
||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override;
|
||||
uint16_t get_num_logs() override;
|
||||
uint16_t start_new_log(void) override;
|
||||
void LogReadProcess(const uint16_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
print_mode_fn print_mode,
|
||||
AP_HAL::BetterStream *port);
|
||||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||
AP_HAL::BetterStream *port) override;
|
||||
void DumpPageInfo(AP_HAL::BetterStream *port) override;
|
||||
void ShowDeviceInfo(AP_HAL::BetterStream *port) override;
|
||||
void ListAvailableLogs(AP_HAL::BetterStream *port) override;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
void flush(void);
|
||||
void flush(void) override;
|
||||
#endif
|
||||
void periodic_1Hz(const uint32_t now) override;
|
||||
void periodic_fullrate(const uint32_t now);
|
||||
void periodic_fullrate(const uint32_t now) override;
|
||||
|
||||
// this method is used when reporting system status over mavlink
|
||||
bool logging_enabled() const;
|
||||
bool logging_failed() const;
|
||||
bool logging_enabled() const override;
|
||||
bool logging_failed() const override;
|
||||
|
||||
void vehicle_was_disarmed() override;
|
||||
|
||||
|
@ -124,7 +124,7 @@ private:
|
|||
uint32_t _get_log_size(const uint16_t log_num) const;
|
||||
uint32_t _get_log_time(const uint16_t log_num) const;
|
||||
|
||||
void stop_logging(void);
|
||||
void stop_logging(void) override;
|
||||
|
||||
void _io_timer(void);
|
||||
|
||||
|
|
|
@ -34,7 +34,7 @@ public:
|
|||
|
||||
bool logging_started() const override { return _logging_started; }
|
||||
|
||||
void stop_logging();
|
||||
void stop_logging() override;
|
||||
|
||||
/* Write a block of data at current offset */
|
||||
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size,
|
||||
|
@ -78,12 +78,12 @@ public:
|
|||
struct dm_block *next;
|
||||
};
|
||||
void push_log_blocks();
|
||||
virtual bool send_log_block(struct dm_block &block);
|
||||
virtual void handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t seqno);
|
||||
virtual void handle_retry(uint32_t block_num);
|
||||
bool send_log_block(struct dm_block &block);
|
||||
void handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t seqno);
|
||||
void handle_retry(uint32_t block_num);
|
||||
void do_resends(uint32_t now);
|
||||
virtual void set_channel(mavlink_channel_t chan);
|
||||
virtual void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;
|
||||
void set_channel(mavlink_channel_t chan);
|
||||
void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;
|
||||
void free_all_blocks();
|
||||
|
||||
// a stack for free blocks, queues for pending, sent, retries and sent
|
||||
|
@ -126,8 +126,8 @@ protected:
|
|||
} stats;
|
||||
|
||||
// this method is used when reporting system status over mavlink
|
||||
bool logging_enabled() const { return true; }
|
||||
bool logging_failed() const;
|
||||
bool logging_enabled() const override { return true; }
|
||||
bool logging_failed() const override;
|
||||
|
||||
private:
|
||||
mavlink_channel_t _chan;
|
||||
|
@ -166,9 +166,9 @@ private:
|
|||
struct dm_block *_current_block;
|
||||
struct dm_block *next_block();
|
||||
|
||||
void periodic_10Hz(uint32_t now);
|
||||
void periodic_1Hz(uint32_t now);
|
||||
void periodic_fullrate(uint32_t now);
|
||||
void periodic_10Hz(uint32_t now) override;
|
||||
void periodic_1Hz(uint32_t now) override;
|
||||
void periodic_fullrate(uint32_t now) override;
|
||||
|
||||
void stats_init();
|
||||
void stats_reset();
|
||||
|
|
Loading…
Reference in New Issue