AP_Logger_MAVLink.h 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184
  1. /*
  2. AP_Logger logging - MAVLink variant
  3. - transfers blocks of the open log file to a client using MAVLink
  4. */
  5. #pragma once
  6. #define LOGGER_MAVLINK_SUPPORT 1
  7. #if LOGGER_MAVLINK_SUPPORT
  8. #include <AP_HAL/AP_HAL.h>
  9. #include "AP_Logger_Backend.h"
  10. extern const AP_HAL::HAL& hal;
  11. #define DF_MAVLINK_DISABLE_INTERRUPTS 0
  12. class AP_Logger_MAVLink : public AP_Logger_Backend
  13. {
  14. public:
  15. // constructor
  16. AP_Logger_MAVLink(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) :
  17. AP_Logger_Backend(front, writer),
  18. _max_blocks_per_send_blocks(8)
  19. ,_perf_packing(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DM_packing"))
  20. {
  21. _blockcount = 1024*((uint8_t)_front._params.mav_bufsize) / sizeof(struct dm_block);
  22. // ::fprintf(stderr, "DM: Using %u blocks\n", _blockcount);
  23. }
  24. // initialisation
  25. void Init() override;
  26. // in actual fact, we throw away everything until a client connects.
  27. // This stops calls to start_new_log from the vehicles
  28. bool logging_started() const override { return _initialised; }
  29. void stop_logging() override;
  30. /* Write a block of data at current offset */
  31. bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size,
  32. bool is_critical) override;
  33. // initialisation
  34. bool CardInserted(void) const override { return true; }
  35. // erase handling
  36. void EraseAll() override {}
  37. bool NeedPrep() override { return false; }
  38. void Prep() override { }
  39. // high level interface
  40. uint16_t find_last_log(void) override { return 0; }
  41. void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override {}
  42. void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override {}
  43. int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override { return 0; }
  44. uint16_t get_num_logs(void) override { return 0; }
  45. void push_log_blocks() override;
  46. void remote_log_block_status_msg(const mavlink_channel_t chan, const mavlink_message_t& msg) override;
  47. protected:
  48. bool WritesOK() const override;
  49. private:
  50. struct dm_block {
  51. uint32_t seqno;
  52. uint8_t buf[MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN];
  53. uint32_t last_sent;
  54. struct dm_block *next;
  55. };
  56. bool send_log_block(struct dm_block &block);
  57. void handle_ack(const mavlink_channel_t chan, const mavlink_message_t &msg, uint32_t seqno);
  58. void handle_retry(uint32_t block_num);
  59. void do_resends(uint32_t now);
  60. void free_all_blocks();
  61. // a stack for free blocks, queues for pending, sent, retries and sent
  62. struct dm_block_queue {
  63. uint32_t sent_count;
  64. struct dm_block *oldest;
  65. struct dm_block *youngest;
  66. };
  67. typedef struct dm_block_queue dm_block_queue_t ;
  68. void enqueue_block(dm_block_queue_t &queue, struct dm_block *block);
  69. bool queue_has_block(dm_block_queue_t &queue, struct dm_block *block);
  70. struct dm_block *dequeue_seqno(dm_block_queue_t &queue, uint32_t seqno);
  71. bool free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue);
  72. bool send_log_blocks_from_queue(dm_block_queue_t &queue);
  73. uint8_t stack_size(struct dm_block *stack);
  74. uint8_t queue_size(dm_block_queue_t queue);
  75. struct dm_block *_blocks_free;
  76. dm_block_queue_t _blocks_sent;
  77. dm_block_queue_t _blocks_pending;
  78. dm_block_queue_t _blocks_retry;
  79. struct _stats {
  80. // the following are reset any time we log stats (see "reset_stats")
  81. uint32_t resends;
  82. uint8_t collection_count;
  83. uint16_t state_free; // cumulative across collection period
  84. uint8_t state_free_min;
  85. uint8_t state_free_max;
  86. uint16_t state_pending; // cumulative across collection period
  87. uint8_t state_pending_min;
  88. uint8_t state_pending_max;
  89. uint16_t state_retry; // cumulative across collection period
  90. uint8_t state_retry_min;
  91. uint8_t state_retry_max;
  92. uint16_t state_sent; // cumulative across collection period
  93. uint8_t state_sent_min;
  94. uint8_t state_sent_max;
  95. } stats;
  96. // this method is used when reporting system status over mavlink
  97. bool logging_enabled() const override { return true; }
  98. bool logging_failed() const override;
  99. mavlink_channel_t _chan;
  100. uint8_t _target_system_id;
  101. uint8_t _target_component_id;
  102. // this controls the maximum number of blocks we will push from
  103. // the pending and send queues in any call to push_log_blocks.
  104. // push_log_blocks is called by periodic_tasks. Each block is 200
  105. // bytes. In Plane, at 50Hz, a _max_blocks_per_send_blocks of 2
  106. // means we will push at most 2*50*200 == 20KB of logs per second
  107. // _max_blocks_per_send_blocks has to be high enough to push all
  108. // of the logs, but low enough that we don't spend way too much
  109. // time packing messages in any one loop
  110. const uint8_t _max_blocks_per_send_blocks;
  111. uint32_t _next_seq_num;
  112. uint16_t _latest_block_len;
  113. uint32_t _last_response_time;
  114. uint32_t _last_send_time;
  115. uint8_t _next_block_number_to_resend;
  116. bool _sending_to_client;
  117. void Write_logger_MAV(AP_Logger_MAVLink &logger);
  118. uint32_t bufferspace_available() override; // in bytes
  119. uint8_t remaining_space_in_current_block();
  120. // write buffer
  121. uint8_t _blockcount_free;
  122. uint8_t _blockcount;
  123. struct dm_block *_blocks;
  124. struct dm_block *_current_block;
  125. struct dm_block *next_block();
  126. void periodic_10Hz(uint32_t now) override;
  127. void periodic_1Hz() override;
  128. void periodic_fullrate() override;
  129. void stats_init();
  130. void stats_reset();
  131. void stats_collect();
  132. void stats_log();
  133. uint32_t _stats_last_collected_time;
  134. uint32_t _stats_last_logged_time;
  135. uint8_t mavlink_seq;
  136. /* we currently ignore requests to start a new log. Notionally we
  137. * could close the currently logging session and hope the client
  138. * re-opens one */
  139. uint16_t start_new_log(void) override {
  140. return 0;
  141. }
  142. // performance counters
  143. AP_HAL::Util::perf_counter_t _perf_errors;
  144. AP_HAL::Util::perf_counter_t _perf_packing;
  145. AP_HAL::Util::perf_counter_t _perf_overruns;
  146. HAL_Semaphore semaphore;
  147. };
  148. #endif // LOGGER_MAVLINK_SUPPORT