APM:Libraries
DataFlash_MAVLink.cpp
Go to the documentation of this file.
1 /*
2  DataFlash Remote(via MAVLink) logging
3 */
4 
5 #include "DataFlash_MAVLink.h"
6 
7 #if DATAFLASH_MAVLINK_SUPPORT
8 
9 #include "LogStructure.h"
10 
11 #define REMOTE_LOG_DEBUGGING 0
12 
13 #if REMOTE_LOG_DEBUGGING
14 #include <stdio.h>
15  # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
16 #else
17  # define Debug(fmt, args ...)
18 #endif
19 
20 #include <GCS_MAVLink/GCS.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 
25 // initialisation
27 {
28  semaphore = hal.util->new_semaphore();
29  if (semaphore == nullptr) {
30  AP_HAL::panic("Failed to create DataFlash_MAVLink semaphore");
31  return;
32  }
33 
35 
36  _blocks = nullptr;
37  while (_blockcount >= 8) { // 8 is a *magic* number
38  _blocks = (struct dm_block *) calloc(_blockcount, sizeof(struct dm_block));
39  if (_blocks != nullptr) {
40  break;
41  }
42  _blockcount /= 2;
43  }
44 
45  if (_blocks == nullptr) {
46  return;
47  }
48 
50  stats_init();
51 
52  _initialised = true;
53 }
54 
56 {
57  return !_sending_to_client;
58 }
59 
62 }
63 
65  // note that _current_block *could* be NULL ATM.
66  return (MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN - _latest_block_len);
67 }
68 
70 {
71  if (queue.youngest != nullptr) {
72  queue.youngest->next = block;
73  } else {
74  queue.oldest = block;
75  }
76  queue.youngest = block;
77 }
78 
80 {
81  struct dm_block *prev = nullptr;
82  for (struct dm_block *block=queue.oldest; block != nullptr; block=block->next) {
83  if (block->seqno == seqno) {
84  if (prev == nullptr) {
85  if (queue.youngest == queue.oldest) {
86  queue.oldest = nullptr;
87  queue.youngest = nullptr;
88  } else {
89  queue.oldest = block->next;
90  }
91  } else {
92  if (queue.youngest == block) {
93  queue.youngest = prev;
94  }
95  prev->next = block->next;
96  }
97  block->next = nullptr;
98  return block;
99  }
100  prev = block;
101  }
102  return nullptr;
103 }
104 
106 {
107  struct dm_block *block = dequeue_seqno(queue, seqno);
108  if (block != nullptr) {
109  block->next = _blocks_free;
110  _blocks_free = block;
111  _blockcount_free++; // comment me out to expose a bug!
112  return true;
113  }
114  return false;
115 }
116 
117 
119 {
120  if (!_sending_to_client) {
121  return false;
122  }
123  return true;
124 }
125 
126 /* Write a block of data at current offset */
127 
128 // DM_write: 70734 events, 0 overruns, 167806us elapsed, 2us avg, min 1us max 34us 0.620us rms
129 bool DataFlash_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
130 {
131  if (!semaphore->take_nonblocking()) {
132  _dropped++;
133  return false;
134  }
135 
137  semaphore->give();
138  return false;
139  }
140 
141  if (bufferspace_available() < size) {
143  // do not count the startup packets as being dropped...
144  _dropped++;
145  }
146  semaphore->give();
147  return false;
148  }
149 
150  uint16_t copied = 0;
151 
152  while (copied < size) {
153  if (_current_block == nullptr) {
155  if (_current_block == nullptr) {
156  // should not happen - there's a sanity check above
157  internal_error();
158  semaphore->give();
159  return false;
160  }
161  }
162  uint16_t remaining_to_copy = size - copied;
163  uint16_t _curr_remaining = remaining_space_in_current_block();
164  uint16_t to_copy = (remaining_to_copy > _curr_remaining) ? _curr_remaining : remaining_to_copy;
165  memcpy(&(_current_block->buf[_latest_block_len]), &((const uint8_t *)pBuffer)[copied], to_copy);
166  copied += to_copy;
167  _latest_block_len += to_copy;
168  if (_latest_block_len == MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN) {
169  //block full, mark it to be sent:
172  }
173  }
174 
175  semaphore->give();
176 
177  return true;
178 }
179 
180 //Get a free block
182 {
184  if (ret != nullptr) {
185  _blocks_free = ret->next;
187  ret->seqno = _next_seq_num++;
188  ret->last_sent = 0;
189  ret->next = nullptr;
190  _latest_block_len = 0;
191  }
192  return ret;
193 }
194 
196 {
197  _blocks_free = nullptr;
198  _current_block = nullptr;
199 
206 
207  // add blocks to the free stack:
208  for(uint8_t i=0; i < _blockcount; i++) {
210  _blocks_free = &_blocks[i];
211  // this value doesn't really matter, but it stops valgrind
212  // complaining when acking blocks (we check seqno before
213  // state). Also, when we receive ACKs we check seqno, and we
214  // want to ack the *real* block zero!
215  _blocks[i].seqno = 9876543;
216  }
218 
219  _latest_block_len = 0;
220 }
221 
223 {
224  if (_sending_to_client) {
225  _sending_to_client = false;
227  }
228 }
229 
230 void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan,
231  mavlink_message_t* msg,
232  uint32_t seqno)
233 {
234  if (!_initialised) {
235  return;
236  }
237  if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_STOP) {
238  Debug("Received stop-logging packet");
239  stop_logging();
240  return;
241  }
242  if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_START) {
243  if (!_sending_to_client) {
244  Debug("Starting New Log");
245  free_all_blocks();
246  // _current_block = next_block();
247  // if (_current_block == nullptr) {
248  // Debug("No free blocks?!!!\n");
249  // return;
250  // }
251  stats_init();
252  _sending_to_client = true;
253  _target_system_id = msg->sysid;
254  _target_component_id = msg->compid;
255  _chan = chan;
256  _next_seq_num = 0;
259  Debug("Target: (%u/%u)", _target_system_id, _target_component_id);
260  }
261  return;
262  }
263 
264  // check SENT blocks (VERY likely to be first on the list):
265  if (free_seqno_from_queue(seqno, _blocks_sent)) {
266  // celebrate
268  } else if(free_seqno_from_queue(seqno, _blocks_retry)) {
269  // party
271  } else {
272  // probably acked already and put on the free list.
273  }
274 }
275 
277  mavlink_message_t* msg)
278 {
279  mavlink_remote_log_block_status_t packet;
280  mavlink_msg_remote_log_block_status_decode(msg, &packet);
281  if (!semaphore->take_nonblocking()) {
282  return;
283  }
284  if(packet.status == 0){
285  handle_retry(packet.seqno);
286  } else{
287  handle_ack(chan, msg, packet.seqno);
288  }
289  semaphore->give();
290 }
291 
293 {
294  if (!_initialised || !_sending_to_client) {
295  return;
296  }
297 
298  struct dm_block *victim = dequeue_seqno(_blocks_sent, seqno);
299  if (victim != nullptr) {
301  enqueue_block(_blocks_retry, victim);
302  }
303 }
304 
306  _dropped = 0;
307  _internal_errors = 0;
308  stats.resends = 0;
309  stats_reset();
310 }
312  stats.state_free = 0;
313  stats.state_free_min = -1; // unsigned wrap
314  stats.state_free_max = 0;
315  stats.state_pending = 0;
316  stats.state_pending_min = -1; // unsigned wrap
318  stats.state_retry = 0;
319  stats.state_retry_min = -1; // unsigned wrap
321  stats.state_sent = 0;
322  stats.state_sent_min = -1; // unsigned wrap
323  stats.state_sent_max = 0;
325 }
326 
328 {
329  if (df.stats.collection_count == 0) {
330  return;
331  }
332  struct log_DF_MAV_Stats pkt = {
335  seqno : df._next_seq_num-1,
336  dropped : df._dropped,
338  resends : df.stats.resends,
349  };
350  WriteBlock(&pkt,sizeof(pkt));
351 }
352 
354 {
355  if (!_initialised) {
356  return;
357  }
358  if (stats.collection_count == 0) {
359  return;
360  }
361  Log_Write_DF_MAV(*this);
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",
364  dropped,
366  stats.resends,
380  );
381 #endif
382  stats_reset();
383 }
384 
386 {
387  uint8_t ret = 0;
388  for (struct dm_block *block=stack; block != nullptr; block=block->next) {
389  ret++;
390  }
391  return ret;
392 }
394 {
395  return stack_size(queue.oldest);
396 }
397 
399 {
400  if (!_initialised) {
401  return;
402  }
403  if (!semaphore->take_nonblocking()) {
404  return;
405  }
406  uint8_t pending = queue_size(_blocks_pending);
407  uint8_t sent = queue_size(_blocks_sent);
408  uint8_t retry = queue_size(_blocks_retry);
409  uint8_t sfree = stack_size(_blocks_free);
410 
411  if (sfree != _blockcount_free) {
412  internal_error();
413  }
414  semaphore->give();
415 
416  stats.state_pending += pending;
417  stats.state_sent += sent;
418  stats.state_free += sfree;
419  stats.state_retry += retry;
420 
421  if (pending < stats.state_pending_min) {
422  stats.state_pending_min = pending;
423  }
424  if (pending > stats.state_pending_max) {
425  stats.state_pending_max = pending;
426  }
427  if (retry < stats.state_retry_min) {
428  stats.state_retry_min = retry;
429  }
430  if (retry > stats.state_retry_max) {
431  stats.state_retry_max = retry;
432  }
433  if (sent < stats.state_sent_min) {
434  stats.state_sent_min = sent;
435  }
436  if (sent > stats.state_sent_max) {
437  stats.state_sent_max = sent;
438  }
439  if (sfree < stats.state_free_min) {
440  stats.state_free_min = sfree;
441  }
442  if (sfree > stats.state_free_max) {
443  stats.state_free_max = sfree;
444  }
445 
447 }
448 
449 /* while we "successfully" send log blocks from a queue, move them to
450  * the sent list. DO NOT call this for blocks already sent!
451 */
453 {
454  uint8_t sent_count = 0;
455  while (queue.oldest != nullptr) {
456  if (sent_count++ > _max_blocks_per_send_blocks) {
457  return false;
458  }
459  if (! send_log_block(*queue.oldest)) {
460  return false;
461  }
462  queue.sent_count++;
463  struct DataFlash_MAVLink::dm_block *tmp = dequeue_seqno(queue,queue.oldest->seqno);
464  if (tmp != nullptr) { // should never be nullptr
466  } else {
467  internal_error();
468  }
469  }
470  return true;
471 }
472 
474 {
475  if (!_initialised || !_sending_to_client) {
476  return;
477  }
478 
480 
481  if (!semaphore->take_nonblocking()) {
482  return;
483  }
484 
486  semaphore->give();
487  return;
488  }
489 
491  semaphore->give();
492  return;
493  }
494  semaphore->give();
495 }
496 
498 {
499  if (!_initialised || !_sending_to_client) {
500  return;
501  }
502 
503  uint8_t count_to_send = 5;
504  if (_blockcount < count_to_send) {
505  count_to_send = _blockcount;
506  }
507  uint32_t oldest = now - 100; // 100 milliseconds before resend. Hmm.
508  while (count_to_send-- > 0) {
509  if (!semaphore->take_nonblocking()) {
510  return;
511  }
512  for (struct dm_block *block=_blocks_sent.oldest; block != nullptr; block=block->next) {
513  // only want to send blocks every now-and-then:
514  if (block->last_sent < oldest) {
515  if (! send_log_block(*block)) {
516  // failed to send the block; try again later....
517  semaphore->give();
518  return;
519  }
520  stats.resends++;
521  }
522  }
523  semaphore->give();
524  }
525 }
526 
527 // NOTE: any functions called from these periodic functions MUST
528 // handle locking of the blocks structures by taking the semaphore
529 // appropriately!
530 void DataFlash_MAVLink::periodic_10Hz(const uint32_t now)
531 {
532  do_resends(now);
533  stats_collect();
534 }
535 void DataFlash_MAVLink::periodic_1Hz(const uint32_t now)
536 {
537  if (_sending_to_client &&
539  // other end appears to have timed out!
540  Debug("Client timed out");
541  _sending_to_client = false;
542  return;
543  }
544  stats_log();
545 }
546 
548 {
549  push_log_blocks();
550 }
551 
552 //TODO: handle full txspace properly
554 {
555  mavlink_channel_t chan = mavlink_channel_t(_chan - MAVLINK_COMM_0);
556  if (!_initialised) {
557  return false;
558  }
559  if (!HAVE_PAYLOAD_SPACE(chan, REMOTE_LOG_DATA_BLOCK)) {
560  return false;
561  }
562  if (comm_get_txspace(chan) < 500) {
563  return false;
564  }
565 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
566  if (rand() < 0.1) {
567  return false;
568  }
569 #endif
570 
571 #if DF_MAVLINK_DISABLE_INTERRUPTS
572  irqstate_t istate = irqsave();
573 #endif
574 
575 // DM_packing: 267039 events, 0 overruns, 8440834us elapsed, 31us avg, min 31us max 32us 0.488us rms
577 
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;
581  chan_status->current_tx_seq = mavlink_seq++;
582  // Debug("Sending block (%d)", block.seqno);
583  mavlink_msg_remote_log_data_block_pack(mavlink_system.sysid,
584  MAV_COMP_ID_LOG,
585  &msg,
588  block.seqno,
589  block.buf);
590 
592 
593 #if DF_MAVLINK_DISABLE_INTERRUPTS
594  irqrestore(istate);
595 #endif
596 
597  block.last_sent = AP_HAL::millis();
598  chan_status->current_tx_seq = saved_seq;
599 
600  // _last_send_time is set even if we fail to send the packet; if
601  // the txspace is repeatedly chockas we should not add to the
602  // problem and stop attempting to log
604 
605  _mavlink_resend_uart(chan, &msg);
606 
607  return true;
608 }
609 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
virtual void WriteMoreStartupMessages()
uint8_t state_sent_min
Definition: LogStructure.h:881
DFMessageWriter_DFLogStart * _startup_messagewriter
uint8_t state_pending_min
Definition: LogStructure.h:878
uint8_t state_pending_max
Definition: LogStructure.h:879
virtual void start_new_log_reset_variables()
Interface definition for the various Ground Control System.
virtual void Init()
uint8_t state_sent_max
Definition: LogStructure.h:882
uint32_t timestamp
Definition: LogStructure.h:868
AP_HAL::Util * util
Definition: HAL.h:115
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
uint8_t state_free_min
Definition: LogStructure.h:875
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
uint8_t state_pending_avg
Definition: LogStructure.h:877
virtual bool take_nonblocking() WARN_IF_UNUSED=0
virtual bool WriteBlockCheckStartupMessages()
uint32_t millis()
Definition: system.cpp:157
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
virtual bool give()=0
uint8_t state_free_avg
Definition: LogStructure.h:874
uint8_t state_sent_avg
Definition: LogStructure.h:880
uint8_t state_free_max
Definition: LogStructure.h:876
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint8_t internal_errors
Definition: LogStructure.h:873
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool WriteBlock(const void *pBuffer, uint16_t size)
virtual bool finished()
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8