APM:Libraries
DataFlash_MAVLink.h
Go to the documentation of this file.
1 /*
2  DataFlash logging - MAVLink variant
3 
4  - transfers blocks of the open log file to a client using MAVLink
5  */
6 #pragma once
7 
8 #define DATAFLASH_MAVLINK_SUPPORT 1
9 
10 #if DATAFLASH_MAVLINK_SUPPORT
11 
12 #include <AP_HAL/AP_HAL.h>
13 
14 #include "DataFlash_Backend.h"
15 
16 extern const AP_HAL::HAL& hal;
17 
18 #define DF_MAVLINK_DISABLE_INTERRUPTS 0
19 
21 {
22 public:
23  // constructor
25  DataFlash_Backend(front, writer),
27  ,_perf_packing(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DM_packing"))
28  {
29  _blockcount = 1024*((uint8_t)_front._params.mav_bufsize) / sizeof(struct dm_block);
30  // ::fprintf(stderr, "DM: Using %u blocks\n", _blockcount);
31  }
32 
33  // initialisation
34  void Init() override;
35 
36  // in actual fact, we throw away everything until a client connects.
37  // This stops calls to start_new_log from the vehicles
38  bool logging_started() const override { return _initialised; }
39 
40  void stop_logging() override;
41 
42  /* Write a block of data at current offset */
43  bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size,
44  bool is_critical) override;
45 
46  // initialisation
47  bool CardInserted(void) const override { return true; }
48 
49  // erase handling
50  void EraseAll() override {}
51 
52  bool NeedPrep() override { return false; }
53  void Prep() override { }
54 
55  // high level interface
56  uint16_t find_last_log(void) override { return 0; }
57  void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) override {}
58  void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) 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; }
60  uint16_t get_num_logs(void) override { return 0; }
61 
62  void push_log_blocks() override;
63 
64  void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;
65 
66 protected:
67 
68  bool WritesOK() const override;
69 
70 private:
71 
72  struct dm_block {
73  uint32_t seqno;
74  uint8_t buf[MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN];
75  uint32_t last_sent;
76  struct dm_block *next;
77  };
78  bool send_log_block(struct dm_block &block);
79  void handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t seqno);
80  void handle_retry(uint32_t block_num);
81  void do_resends(uint32_t now);
82  void free_all_blocks();
83 
84  // a stack for free blocks, queues for pending, sent, retries and sent
85  struct dm_block_queue {
86  uint32_t sent_count;
87  struct dm_block *oldest;
88  struct dm_block *youngest;
89  };
91  void enqueue_block(dm_block_queue_t &queue, struct dm_block *block);
92  bool queue_has_block(dm_block_queue_t &queue, struct dm_block *block);
93  struct dm_block *dequeue_seqno(dm_block_queue_t &queue, uint32_t seqno);
94  bool free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue);
96  uint8_t stack_size(struct dm_block *stack);
97  uint8_t queue_size(dm_block_queue_t queue);
98 
103 
104  struct _stats {
105  // the following are reset any time we log stats (see "reset_stats")
106  uint32_t resends;
108  uint16_t state_free; // cumulative across collection period
109  uint8_t state_free_min;
110  uint8_t state_free_max;
111  uint16_t state_pending; // cumulative across collection period
114  uint16_t state_retry; // cumulative across collection period
117  uint16_t state_sent; // cumulative across collection period
118  uint8_t state_sent_min;
119  uint8_t state_sent_max;
120  } stats;
121 
122  // this method is used when reporting system status over mavlink
123  bool logging_enabled() const override { return true; }
124  bool logging_failed() const override;
125 
126  mavlink_channel_t _chan;
129 
130  // this controls the maximum number of blocks we will push from
131  // the pending and send queues in any call to push_log_blocks.
132  // push_log_blocks is called by periodic_tasks. Each block is 200
133  // bytes. In Plane, at 50Hz, a _max_blocks_per_send_blocks of 2
134  // means we will push at most 2*50*200 == 20KB of logs per second
135  // _max_blocks_per_send_blocks has to be high enough to push all
136  // of the logs, but low enough that we don't spend way too much
137  // time packing messages in any one loop
139 
140  uint32_t _next_seq_num;
143  uint32_t _last_send_time;
146 
148 
149  uint32_t bufferspace_available() override; // in bytes
151  // write buffer
153  uint8_t _blockcount;
154  struct dm_block *_blocks;
156  struct dm_block *next_block();
157 
158  void periodic_10Hz(uint32_t now) override;
159  void periodic_1Hz(uint32_t now) override;
160  void periodic_fullrate(uint32_t now) override;
161 
162  void stats_init();
163  void stats_reset();
164  void stats_collect();
165  void stats_log();
168  uint8_t mavlink_seq;
169 
170  /* we currently ignore requests to start a new log. Notionally we
171  * could close the currently logging session and hope the client
172  * re-opens one */
173  uint16_t start_new_log(void) override {
174  return 0;
175  }
176  bool ReadBlock(void *pkt, uint16_t size) override {
177  return false;
178  }
179  // performance counters
183 
185 };
186 
187 #endif // DATAFLASH_MAVLINK_SUPPORT
struct DataFlash_Class::@194 _params
void * perf_counter_t
Definition: Util.h:101
DataFlash_Class & _front
static uint16_t log_num
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
AP_Int8 mav_bufsize
Definition: DataFlash.h:201