AP_Logger_MAVLink.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601
  1. /*
  2. AP_Logger Remote(via MAVLink) logging
  3. */
  4. #include "AP_Logger_MAVLink.h"
  5. #if LOGGER_MAVLINK_SUPPORT
  6. #include "LogStructure.h"
  7. #define REMOTE_LOG_DEBUGGING 0
  8. #if REMOTE_LOG_DEBUGGING
  9. #include <stdio.h>
  10. # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
  11. #else
  12. # define Debug(fmt, args ...)
  13. #endif
  14. #include <AP_InternalError/AP_InternalError.h>
  15. #include <GCS_MAVLink/GCS.h>
  16. extern const AP_HAL::HAL& hal;
  17. // initialisation
  18. void AP_Logger_MAVLink::Init()
  19. {
  20. AP_Logger_Backend::Init();
  21. _blocks = nullptr;
  22. while (_blockcount >= 8) { // 8 is a *magic* number
  23. _blocks = (struct dm_block *) calloc(_blockcount, sizeof(struct dm_block));
  24. if (_blocks != nullptr) {
  25. break;
  26. }
  27. _blockcount /= 2;
  28. }
  29. if (_blocks == nullptr) {
  30. return;
  31. }
  32. free_all_blocks();
  33. stats_init();
  34. _initialised = true;
  35. }
  36. bool AP_Logger_MAVLink::logging_failed() const
  37. {
  38. return !_sending_to_client;
  39. }
  40. uint32_t AP_Logger_MAVLink::bufferspace_available() {
  41. return (_blockcount_free * 200 + remaining_space_in_current_block());
  42. }
  43. uint8_t AP_Logger_MAVLink::remaining_space_in_current_block() {
  44. // note that _current_block *could* be NULL ATM.
  45. return (MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN - _latest_block_len);
  46. }
  47. void AP_Logger_MAVLink::enqueue_block(dm_block_queue_t &queue, struct dm_block *block)
  48. {
  49. if (queue.youngest != nullptr) {
  50. queue.youngest->next = block;
  51. } else {
  52. queue.oldest = block;
  53. }
  54. queue.youngest = block;
  55. }
  56. struct AP_Logger_MAVLink::dm_block *AP_Logger_MAVLink::dequeue_seqno(AP_Logger_MAVLink::dm_block_queue_t &queue, uint32_t seqno)
  57. {
  58. struct dm_block *prev = nullptr;
  59. for (struct dm_block *block=queue.oldest; block != nullptr; block=block->next) {
  60. if (block->seqno == seqno) {
  61. if (prev == nullptr) {
  62. if (queue.youngest == queue.oldest) {
  63. queue.oldest = nullptr;
  64. queue.youngest = nullptr;
  65. } else {
  66. queue.oldest = block->next;
  67. }
  68. } else {
  69. if (queue.youngest == block) {
  70. queue.youngest = prev;
  71. }
  72. prev->next = block->next;
  73. }
  74. block->next = nullptr;
  75. return block;
  76. }
  77. prev = block;
  78. }
  79. return nullptr;
  80. }
  81. bool AP_Logger_MAVLink::free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue)
  82. {
  83. struct dm_block *block = dequeue_seqno(queue, seqno);
  84. if (block != nullptr) {
  85. block->next = _blocks_free;
  86. _blocks_free = block;
  87. _blockcount_free++; // comment me out to expose a bug!
  88. return true;
  89. }
  90. return false;
  91. }
  92. bool AP_Logger_MAVLink::WritesOK() const
  93. {
  94. if (!_sending_to_client) {
  95. return false;
  96. }
  97. return true;
  98. }
  99. /* Write a block of data at current offset */
  100. // DM_write: 70734 events, 0 overruns, 167806us elapsed, 2us avg, min 1us max 34us 0.620us rms
  101. bool AP_Logger_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
  102. {
  103. if (!semaphore.take_nonblocking()) {
  104. _dropped++;
  105. return false;
  106. }
  107. if (! WriteBlockCheckStartupMessages()) {
  108. semaphore.give();
  109. return false;
  110. }
  111. if (bufferspace_available() < size) {
  112. if (_startup_messagewriter->finished()) {
  113. // do not count the startup packets as being dropped...
  114. _dropped++;
  115. }
  116. semaphore.give();
  117. return false;
  118. }
  119. uint16_t copied = 0;
  120. while (copied < size) {
  121. if (_current_block == nullptr) {
  122. _current_block = next_block();
  123. if (_current_block == nullptr) {
  124. // should not happen - there's a sanity check above
  125. AP::internalerror().error(AP_InternalError::error_t::logger_bad_current_block);
  126. semaphore.give();
  127. return false;
  128. }
  129. }
  130. uint16_t remaining_to_copy = size - copied;
  131. uint16_t _curr_remaining = remaining_space_in_current_block();
  132. uint16_t to_copy = (remaining_to_copy > _curr_remaining) ? _curr_remaining : remaining_to_copy;
  133. memcpy(&(_current_block->buf[_latest_block_len]), &((const uint8_t *)pBuffer)[copied], to_copy);
  134. copied += to_copy;
  135. _latest_block_len += to_copy;
  136. if (_latest_block_len == MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN) {
  137. //block full, mark it to be sent:
  138. enqueue_block(_blocks_pending, _current_block);
  139. _current_block = next_block();
  140. }
  141. }
  142. semaphore.give();
  143. return true;
  144. }
  145. //Get a free block
  146. struct AP_Logger_MAVLink::dm_block *AP_Logger_MAVLink::next_block()
  147. {
  148. AP_Logger_MAVLink::dm_block *ret = _blocks_free;
  149. if (ret != nullptr) {
  150. _blocks_free = ret->next;
  151. _blockcount_free--;
  152. ret->seqno = _next_seq_num++;
  153. ret->last_sent = 0;
  154. ret->next = nullptr;
  155. _latest_block_len = 0;
  156. }
  157. return ret;
  158. }
  159. void AP_Logger_MAVLink::free_all_blocks()
  160. {
  161. _blocks_free = nullptr;
  162. _current_block = nullptr;
  163. _blocks_pending.sent_count = 0;
  164. _blocks_pending.oldest = _blocks_pending.youngest = nullptr;
  165. _blocks_retry.sent_count = 0;
  166. _blocks_retry.oldest = _blocks_retry.youngest = nullptr;
  167. _blocks_sent.sent_count = 0;
  168. _blocks_sent.oldest = _blocks_sent.youngest = nullptr;
  169. // add blocks to the free stack:
  170. for(uint8_t i=0; i < _blockcount; i++) {
  171. _blocks[i].next = _blocks_free;
  172. _blocks_free = &_blocks[i];
  173. // this value doesn't really matter, but it stops valgrind
  174. // complaining when acking blocks (we check seqno before
  175. // state). Also, when we receive ACKs we check seqno, and we
  176. // want to ack the *real* block zero!
  177. _blocks[i].seqno = 9876543;
  178. }
  179. _blockcount_free = _blockcount;
  180. _latest_block_len = 0;
  181. }
  182. void AP_Logger_MAVLink::stop_logging()
  183. {
  184. if (_sending_to_client) {
  185. _sending_to_client = false;
  186. _last_response_time = AP_HAL::millis();
  187. }
  188. }
  189. void AP_Logger_MAVLink::handle_ack(const mavlink_channel_t chan,
  190. const mavlink_message_t &msg,
  191. uint32_t seqno)
  192. {
  193. if (!_initialised) {
  194. return;
  195. }
  196. if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_STOP) {
  197. Debug("Received stop-logging packet");
  198. stop_logging();
  199. return;
  200. }
  201. if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_START) {
  202. if (!_sending_to_client) {
  203. Debug("Starting New Log");
  204. free_all_blocks();
  205. // _current_block = next_block();
  206. // if (_current_block == nullptr) {
  207. // Debug("No free blocks?!!!\n");
  208. // return;
  209. // }
  210. stats_init();
  211. _sending_to_client = true;
  212. _target_system_id = msg.sysid;
  213. _target_component_id = msg.compid;
  214. _chan = chan;
  215. _next_seq_num = 0;
  216. start_new_log_reset_variables();
  217. _last_response_time = AP_HAL::millis();
  218. Debug("Target: (%u/%u)", _target_system_id, _target_component_id);
  219. }
  220. return;
  221. }
  222. // check SENT blocks (VERY likely to be first on the list):
  223. if (free_seqno_from_queue(seqno, _blocks_sent)) {
  224. // celebrate
  225. _last_response_time = AP_HAL::millis();
  226. } else if(free_seqno_from_queue(seqno, _blocks_retry)) {
  227. // party
  228. _last_response_time = AP_HAL::millis();
  229. } else {
  230. // probably acked already and put on the free list.
  231. }
  232. }
  233. void AP_Logger_MAVLink::remote_log_block_status_msg(const mavlink_channel_t chan,
  234. const mavlink_message_t& msg)
  235. {
  236. mavlink_remote_log_block_status_t packet;
  237. mavlink_msg_remote_log_block_status_decode(&msg, &packet);
  238. if (!semaphore.take_nonblocking()) {
  239. return;
  240. }
  241. if(packet.status == 0){
  242. handle_retry(packet.seqno);
  243. } else{
  244. handle_ack(chan, msg, packet.seqno);
  245. }
  246. semaphore.give();
  247. }
  248. void AP_Logger_MAVLink::handle_retry(uint32_t seqno)
  249. {
  250. if (!_initialised || !_sending_to_client) {
  251. return;
  252. }
  253. struct dm_block *victim = dequeue_seqno(_blocks_sent, seqno);
  254. if (victim != nullptr) {
  255. _last_response_time = AP_HAL::millis();
  256. enqueue_block(_blocks_retry, victim);
  257. }
  258. }
  259. void AP_Logger_MAVLink::stats_init() {
  260. _dropped = 0;
  261. stats.resends = 0;
  262. stats_reset();
  263. }
  264. void AP_Logger_MAVLink::stats_reset() {
  265. stats.state_free = 0;
  266. stats.state_free_min = -1; // unsigned wrap
  267. stats.state_free_max = 0;
  268. stats.state_pending = 0;
  269. stats.state_pending_min = -1; // unsigned wrap
  270. stats.state_pending_max = 0;
  271. stats.state_retry = 0;
  272. stats.state_retry_min = -1; // unsigned wrap
  273. stats.state_retry_max = 0;
  274. stats.state_sent = 0;
  275. stats.state_sent_min = -1; // unsigned wrap
  276. stats.state_sent_max = 0;
  277. stats.collection_count = 0;
  278. }
  279. void AP_Logger_MAVLink::Write_logger_MAV(AP_Logger_MAVLink &logger_mav)
  280. {
  281. if (logger_mav.stats.collection_count == 0) {
  282. return;
  283. }
  284. const struct log_MAV_Stats pkt{
  285. LOG_PACKET_HEADER_INIT(LOG_MAV_STATS),
  286. timestamp : AP_HAL::millis(),
  287. seqno : logger_mav._next_seq_num-1,
  288. dropped : logger_mav._dropped,
  289. retries : logger_mav._blocks_retry.sent_count,
  290. resends : logger_mav.stats.resends,
  291. state_free_avg : (uint8_t)(logger_mav.stats.state_free/logger_mav.stats.collection_count),
  292. state_free_min : logger_mav.stats.state_free_min,
  293. state_free_max : logger_mav.stats.state_free_max,
  294. state_pending_avg : (uint8_t)(logger_mav.stats.state_pending/logger_mav.stats.collection_count),
  295. state_pending_min : logger_mav.stats.state_pending_min,
  296. state_pending_max : logger_mav.stats.state_pending_max,
  297. state_sent_avg : (uint8_t)(logger_mav.stats.state_sent/logger_mav.stats.collection_count),
  298. state_sent_min : logger_mav.stats.state_sent_min,
  299. state_sent_max : logger_mav.stats.state_sent_max,
  300. };
  301. WriteBlock(&pkt,sizeof(pkt));
  302. }
  303. void AP_Logger_MAVLink::stats_log()
  304. {
  305. if (!_initialised) {
  306. return;
  307. }
  308. if (stats.collection_count == 0) {
  309. return;
  310. }
  311. Write_logger_MAV(*this);
  312. #if REMOTE_LOG_DEBUGGING
  313. printf("D:%d Retry:%d Resent:%d SF:%d/%d/%d SP:%d/%d/%d SS:%d/%d/%d SR:%d/%d/%d\n",
  314. dropped,
  315. _blocks_retry.sent_count,
  316. stats.resends,
  317. stats.state_free_min,
  318. stats.state_free_max,
  319. stats.state_free/stats.collection_count,
  320. stats.state_pending_min,
  321. stats.state_pending_max,
  322. stats.state_pending/stats.collection_count,
  323. stats.state_sent_min,
  324. stats.state_sent_max,
  325. stats.state_sent/stats.collection_count,
  326. stats.state_retry_min,
  327. stats.state_retry_max,
  328. stats.state_retry/stats.collection_count
  329. );
  330. #endif
  331. stats_reset();
  332. }
  333. uint8_t AP_Logger_MAVLink::stack_size(struct dm_block *stack)
  334. {
  335. uint8_t ret = 0;
  336. for (struct dm_block *block=stack; block != nullptr; block=block->next) {
  337. ret++;
  338. }
  339. return ret;
  340. }
  341. uint8_t AP_Logger_MAVLink::queue_size(dm_block_queue_t queue)
  342. {
  343. return stack_size(queue.oldest);
  344. }
  345. void AP_Logger_MAVLink::stats_collect()
  346. {
  347. if (!_initialised) {
  348. return;
  349. }
  350. if (!semaphore.take_nonblocking()) {
  351. return;
  352. }
  353. uint8_t pending = queue_size(_blocks_pending);
  354. uint8_t sent = queue_size(_blocks_sent);
  355. uint8_t retry = queue_size(_blocks_retry);
  356. uint8_t sfree = stack_size(_blocks_free);
  357. if (sfree != _blockcount_free) {
  358. AP::internalerror().error(AP_InternalError::error_t::logger_blockcount_mismatch);
  359. }
  360. semaphore.give();
  361. stats.state_pending += pending;
  362. stats.state_sent += sent;
  363. stats.state_free += sfree;
  364. stats.state_retry += retry;
  365. if (pending < stats.state_pending_min) {
  366. stats.state_pending_min = pending;
  367. }
  368. if (pending > stats.state_pending_max) {
  369. stats.state_pending_max = pending;
  370. }
  371. if (retry < stats.state_retry_min) {
  372. stats.state_retry_min = retry;
  373. }
  374. if (retry > stats.state_retry_max) {
  375. stats.state_retry_max = retry;
  376. }
  377. if (sent < stats.state_sent_min) {
  378. stats.state_sent_min = sent;
  379. }
  380. if (sent > stats.state_sent_max) {
  381. stats.state_sent_max = sent;
  382. }
  383. if (sfree < stats.state_free_min) {
  384. stats.state_free_min = sfree;
  385. }
  386. if (sfree > stats.state_free_max) {
  387. stats.state_free_max = sfree;
  388. }
  389. stats.collection_count++;
  390. }
  391. /* while we "successfully" send log blocks from a queue, move them to
  392. * the sent list. DO NOT call this for blocks already sent!
  393. */
  394. bool AP_Logger_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue)
  395. {
  396. uint8_t sent_count = 0;
  397. while (queue.oldest != nullptr) {
  398. if (sent_count++ > _max_blocks_per_send_blocks) {
  399. return false;
  400. }
  401. if (! send_log_block(*queue.oldest)) {
  402. return false;
  403. }
  404. queue.sent_count++;
  405. struct AP_Logger_MAVLink::dm_block *tmp = dequeue_seqno(queue,queue.oldest->seqno);
  406. if (tmp != nullptr) { // should never be nullptr
  407. enqueue_block(_blocks_sent, tmp);
  408. } else {
  409. AP::internalerror().error(AP_InternalError::error_t::logger_dequeue_failure);
  410. }
  411. }
  412. return true;
  413. }
  414. void AP_Logger_MAVLink::push_log_blocks()
  415. {
  416. if (!_initialised || !_sending_to_client) {
  417. return;
  418. }
  419. AP_Logger_Backend::WriteMoreStartupMessages();
  420. if (!semaphore.take_nonblocking()) {
  421. return;
  422. }
  423. if (! send_log_blocks_from_queue(_blocks_retry)) {
  424. semaphore.give();
  425. return;
  426. }
  427. if (! send_log_blocks_from_queue(_blocks_pending)) {
  428. semaphore.give();
  429. return;
  430. }
  431. semaphore.give();
  432. }
  433. void AP_Logger_MAVLink::do_resends(uint32_t now)
  434. {
  435. if (!_initialised || !_sending_to_client) {
  436. return;
  437. }
  438. uint8_t count_to_send = 5;
  439. if (_blockcount < count_to_send) {
  440. count_to_send = _blockcount;
  441. }
  442. uint32_t oldest = now - 100; // 100 milliseconds before resend. Hmm.
  443. while (count_to_send-- > 0) {
  444. if (!semaphore.take_nonblocking()) {
  445. return;
  446. }
  447. for (struct dm_block *block=_blocks_sent.oldest; block != nullptr; block=block->next) {
  448. // only want to send blocks every now-and-then:
  449. if (block->last_sent < oldest) {
  450. if (! send_log_block(*block)) {
  451. // failed to send the block; try again later....
  452. semaphore.give();
  453. return;
  454. }
  455. stats.resends++;
  456. }
  457. }
  458. semaphore.give();
  459. }
  460. }
  461. // NOTE: any functions called from these periodic functions MUST
  462. // handle locking of the blocks structures by taking the semaphore
  463. // appropriately!
  464. void AP_Logger_MAVLink::periodic_10Hz(const uint32_t now)
  465. {
  466. do_resends(now);
  467. stats_collect();
  468. }
  469. void AP_Logger_MAVLink::periodic_1Hz()
  470. {
  471. if (_sending_to_client &&
  472. _last_response_time + 10000 < _last_send_time) {
  473. // other end appears to have timed out!
  474. Debug("Client timed out");
  475. _sending_to_client = false;
  476. return;
  477. }
  478. stats_log();
  479. }
  480. void AP_Logger_MAVLink::periodic_fullrate()
  481. {
  482. push_log_blocks();
  483. }
  484. //TODO: handle full txspace properly
  485. bool AP_Logger_MAVLink::send_log_block(struct dm_block &block)
  486. {
  487. mavlink_channel_t chan = mavlink_channel_t(_chan - MAVLINK_COMM_0);
  488. if (!_initialised) {
  489. return false;
  490. }
  491. if (!HAVE_PAYLOAD_SPACE(chan, REMOTE_LOG_DATA_BLOCK)) {
  492. return false;
  493. }
  494. if (comm_get_txspace(chan) < 500) {
  495. return false;
  496. }
  497. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  498. if (rand() < 0.1) {
  499. return false;
  500. }
  501. #endif
  502. #if DF_MAVLINK_DISABLE_INTERRUPTS
  503. irqstate_t istate = irqsave();
  504. #endif
  505. // DM_packing: 267039 events, 0 overruns, 8440834us elapsed, 31us avg, min 31us max 32us 0.488us rms
  506. hal.util->perf_begin(_perf_packing);
  507. mavlink_message_t msg;
  508. mavlink_status_t *chan_status = mavlink_get_channel_status(chan);
  509. uint8_t saved_seq = chan_status->current_tx_seq;
  510. chan_status->current_tx_seq = mavlink_seq++;
  511. // Debug("Sending block (%d)", block.seqno);
  512. mavlink_msg_remote_log_data_block_pack(mavlink_system.sysid,
  513. MAV_COMP_ID_LOG,
  514. &msg,
  515. _target_system_id,
  516. _target_component_id,
  517. block.seqno,
  518. block.buf);
  519. hal.util->perf_end(_perf_packing);
  520. #if DF_MAVLINK_DISABLE_INTERRUPTS
  521. irqrestore(istate);
  522. #endif
  523. block.last_sent = AP_HAL::millis();
  524. chan_status->current_tx_seq = saved_seq;
  525. // _last_send_time is set even if we fail to send the packet; if
  526. // the txspace is repeatedly chockas we should not add to the
  527. // problem and stop attempting to log
  528. _last_send_time = AP_HAL::millis();
  529. _mavlink_resend_uart(chan, &msg);
  530. return true;
  531. }
  532. #endif