7 #if DATAFLASH_MAVLINK_SUPPORT 11 #define REMOTE_LOG_DEBUGGING 0 13 #if REMOTE_LOG_DEBUGGING 15 # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) 17 # define Debug(fmt, args ...) 30 AP_HAL::panic(
"Failed to create DataFlash_MAVLink semaphore");
83 if (block->seqno == seqno) {
84 if (prev ==
nullptr) {
97 block->
next =
nullptr;
108 if (block !=
nullptr) {
152 while (copied < size) {
162 uint16_t remaining_to_copy = size - copied;
164 uint16_t to_copy = (remaining_to_copy > _curr_remaining) ? _curr_remaining : remaining_to_copy;
184 if (ret !=
nullptr) {
231 mavlink_message_t* msg,
237 if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_STOP) {
238 Debug(
"Received stop-logging packet");
242 if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_START) {
244 Debug(
"Starting New Log");
277 mavlink_message_t* msg)
279 mavlink_remote_log_block_status_t packet;
280 mavlink_msg_remote_log_block_status_decode(msg, &packet);
284 if(packet.status == 0){
299 if (victim !=
nullptr) {
362 #if REMOTE_LOG_DEBUGGING 363 printf(
"D:%d Retry:%d Resent:%d E:%d SF:%d/%d/%d SP:%d/%d/%d SS:%d/%d/%d SR:%d/%d/%d\n",
388 for (
struct dm_block *block=stack; block !=
nullptr; block=block->
next) {
454 uint8_t sent_count = 0;
455 while (queue.
oldest !=
nullptr) {
464 if (tmp !=
nullptr) {
503 uint8_t count_to_send = 5;
507 uint32_t oldest = now - 100;
508 while (count_to_send-- > 0) {
514 if (block->last_sent < oldest) {
540 Debug(
"Client timed out");
555 mavlink_channel_t
chan = mavlink_channel_t(
_chan - MAVLINK_COMM_0);
565 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 571 #if DF_MAVLINK_DISABLE_INTERRUPTS 572 irqstate_t istate = irqsave();
578 mavlink_message_t msg;
579 mavlink_status_t *chan_status = mavlink_get_channel_status(chan);
580 uint8_t saved_seq = chan_status->current_tx_seq;
593 #if DF_MAVLINK_DISABLE_INTERRUPTS 598 chan_status->current_tx_seq = saved_seq;
605 _mavlink_resend_uart(chan, &msg);
struct dm_block * youngest
int printf(const char *fmt,...)
virtual void WriteMoreStartupMessages()
uint32_t _last_response_time
struct dm_block * _blocks_free
uint8_t _target_component_id
DFMessageWriter_DFLogStart * _startup_messagewriter
uint8_t state_pending_min
dm_block_queue_t _blocks_sent
uint8_t state_pending_min
uint8_t state_pending_max
uint8_t _target_system_id
virtual void start_new_log_reset_variables()
Interface definition for the various Ground Control System.
bool logging_failed() const override
void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t *msg) override
struct dm_block * _current_block
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) override
bool WritesOK() const override
static int comm_get_txspace(mavlink_channel_t chan)
struct DataFlash_MAVLink::_stats stats
virtual Semaphore * new_semaphore(void)
uint8_t buf[MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN]
AP_HAL::Util::perf_counter_t _perf_packing
void * calloc(size_t nmemb, size_t size)
AP_HAL::Semaphore * semaphore
uint8_t state_pending_max
#define HAVE_PAYLOAD_SPACE(chan, id)
dm_block_queue_t _blocks_retry
uint8_t state_pending_avg
struct dm_block * next_block()
virtual bool take_nonblocking() WARN_IF_UNUSED=0
void enqueue_block(dm_block_queue_t &queue, struct dm_block *block)
virtual bool WriteBlockCheckStartupMessages()
bool send_log_blocks_from_queue(dm_block_queue_t &queue)
struct dm_block * _blocks
mavlink_system_t mavlink_system
MAVLink system definition.
virtual void perf_end(perf_counter_t h)
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 AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
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)
virtual void perf_begin(perf_counter_t h)
#define Debug(fmt, args ...)
AP_HAL::AnalogSource * chan
void periodic_fullrate(uint32_t now) override
void stop_logging() override
void do_resends(uint32_t now)
uint8_t stack_size(struct dm_block *stack)
dm_block_queue_t _blocks_pending
void periodic_10Hz(uint32_t now) override
void panic(const char *errormsg,...) FMT_PRINTF(1
bool WriteBlock(const void *pBuffer, uint16_t size)
void handle_ack(mavlink_channel_t chan, mavlink_message_t *msg, uint32_t seqno)
#define LOG_PACKET_HEADER_INIT(id)
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)