8 #define DATAFLASH_MAVLINK_SUPPORT 1 10 #if DATAFLASH_MAVLINK_SUPPORT 18 #define DF_MAVLINK_DISABLE_INTERRUPTS 0 44 bool is_critical)
override;
59 int16_t
get_log_data(uint16_t
log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
override {
return 0; }
74 uint8_t
buf[MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN];
79 void handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t
seqno);
187 #endif // DATAFLASH_MAVLINK_SUPPORT
struct dm_block * youngest
uint16_t start_new_log(void) override
AP_HAL::Util::perf_counter_t _perf_errors
uint32_t _last_response_time
struct dm_block * _blocks_free
uint8_t _target_component_id
dm_block_queue_t _blocks_sent
uint8_t state_pending_min
uint8_t _target_system_id
uint16_t get_num_logs(void) override
struct DataFlash_Class::@194 _params
bool logging_failed() const override
DataFlash_MAVLink(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t *msg) override
struct dm_block * _current_block
bool logging_started() const override
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) override
bool WritesOK() const override
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page) override
struct DataFlash_MAVLink::_stats stats
uint32_t _stats_last_collected_time
uint8_t buf[MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN]
AP_HAL::Util::perf_counter_t _perf_packing
AP_HAL::Semaphore * semaphore
uint8_t state_pending_max
bool queue_has_block(dm_block_queue_t &queue, struct dm_block *block)
dm_block_queue_t _blocks_retry
AP_HAL::Util::perf_counter_t _perf_overruns
struct dm_block * next_block()
bool ReadBlock(void *pkt, uint16_t size) override
void enqueue_block(dm_block_queue_t &queue, struct dm_block *block)
bool send_log_blocks_from_queue(dm_block_queue_t &queue)
struct dm_block * _blocks
uint8_t _next_block_number_to_resend
uint16_t _latest_block_len
void push_log_blocks() override
void periodic_1Hz(uint32_t now) override
bool send_log_block(struct dm_block &block)
const uint8_t _max_blocks_per_send_blocks
bool free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue)
uint8_t queue_size(dm_block_queue_t queue)
uint32_t _stats_last_logged_time
uint16_t find_last_log(void) override
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override
bool logging_enabled() const override
AP_HAL::AnalogSource * chan
void periodic_fullrate(uint32_t now) override
void stop_logging() override
void do_resends(uint32_t now)
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override
uint8_t stack_size(struct dm_block *stack)
dm_block_queue_t _blocks_pending
void periodic_10Hz(uint32_t now) override
void handle_ack(mavlink_channel_t chan, mavlink_message_t *msg, uint32_t seqno)
uint32_t bufferspace_available() override
uint8_t remaining_space_in_current_block()
void Log_Write_DF_MAV(DataFlash_MAVLink &df)
void handle_retry(uint32_t block_num)
struct dm_block * dequeue_seqno(dm_block_queue_t &queue, uint32_t seqno)
bool CardInserted(void) const override