include_v2.0/mavlink_helpers.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "string.h"
4 #include "checksum.h"
5 #include "mavlink_types.h"
6 #include "mavlink_conversions.h"
7 #include <stdio.h>
8 
9 #ifndef MAVLINK_HELPER
10 #define MAVLINK_HELPER
11 #endif
12 
13 #include "mavlink_sha256.h"
14 
15 #ifdef MAVLINK_USE_CXX_NAMESPACE
16 namespace mavlink {
17 #endif
18 
19 /*
20  * Internal function to give access to the channel status for each channel
21  */
22 #ifndef MAVLINK_GET_CHANNEL_STATUS
24 {
25 #ifdef MAVLINK_EXTERNAL_RX_STATUS
26  // No m_mavlink_status array defined in function,
27  // has to be defined externally
28 #else
29  static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
30 #endif
31  return &m_mavlink_status[chan];
32 }
33 #endif
34 
35 /*
36  * Internal function to give access to the channel buffer for each channel
37  */
38 #ifndef MAVLINK_GET_CHANNEL_BUFFER
40 {
41 
42 #ifdef MAVLINK_EXTERNAL_RX_BUFFER
43  // No m_mavlink_buffer array defined in function,
44  // has to be defined externally
45 #else
46  static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
47 #endif
48  return &m_mavlink_buffer[chan];
49 }
50 #endif // MAVLINK_GET_CHANNEL_BUFFER
51 
56 {
59 }
60 
65  uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN],
66  const uint8_t *header, uint8_t header_len,
67  const uint8_t *packet, uint8_t packet_len,
68  const uint8_t crc[2])
69 {
71  union {
72  uint64_t t64;
73  uint8_t t8[8];
74  } tstamp;
75  if (signing == NULL || !(signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
76  return 0;
77  }
78  signature[0] = signing->link_id;
79  tstamp.t64 = signing->timestamp;
80  memcpy(&signature[1], tstamp.t8, 6);
81  signing->timestamp++;
82 
83  mavlink_sha256_init(&ctx);
84  mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
85  mavlink_sha256_update(&ctx, header, header_len);
86  mavlink_sha256_update(&ctx, packet, packet_len);
87  mavlink_sha256_update(&ctx, crc, 2);
88  mavlink_sha256_update(&ctx, signature, 7);
89  mavlink_sha256_final_48(&ctx, &signature[7]);
90 
92 }
93 
101 MAVLINK_HELPER uint8_t _mav_trim_payload(const char *payload, uint8_t length)
102 {
103  while (length > 1 && payload[length-1] == 0) {
104  length--;
105  }
106  return length;
107 }
108 
113  mavlink_signing_streams_t *signing_streams,
114  const mavlink_message_t *msg)
115 {
116  if (signing == NULL) {
117  return true;
118  }
119  const uint8_t *p = (const uint8_t *)&msg->magic;
120  const uint8_t *psig = msg->signature;
121  const uint8_t *incoming_signature = psig+7;
122  mavlink_sha256_ctx ctx;
123  uint8_t signature[6];
124  uint16_t i;
125 
126  mavlink_sha256_init(&ctx);
127  mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
129  mavlink_sha256_update(&ctx, msg->ck, 2);
130  mavlink_sha256_update(&ctx, psig, 1+6);
131  mavlink_sha256_final_48(&ctx, signature);
132  if (memcmp(signature, incoming_signature, 6) != 0) {
133  return false;
134  }
135 
136  // now check timestamp
137  union tstamp {
138  uint64_t t64;
139  uint8_t t8[8];
140  } tstamp;
141  uint8_t link_id = psig[0];
142  tstamp.t64 = 0;
143  memcpy(tstamp.t8, psig+1, 6);
144 
145  if (signing_streams == NULL) {
146  return false;
147  }
148 
149  // find stream
150  for (i=0; i<signing_streams->num_signing_streams; i++) {
151  if (msg->sysid == signing_streams->stream[i].sysid &&
152  msg->compid == signing_streams->stream[i].compid &&
153  link_id == signing_streams->stream[i].link_id) {
154  break;
155  }
156  }
157  if (i == signing_streams->num_signing_streams) {
158  if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) {
159  // over max number of streams
160  return false;
161  }
162  // new stream. Only accept if timestamp is not more than 1 minute old
163  if (tstamp.t64 + 6000*1000UL < signing->timestamp) {
164  return false;
165  }
166  // add new stream
167  signing_streams->stream[i].sysid = msg->sysid;
168  signing_streams->stream[i].compid = msg->compid;
169  signing_streams->stream[i].link_id = link_id;
170  signing_streams->num_signing_streams++;
171  } else {
172  union tstamp last_tstamp;
173  last_tstamp.t64 = 0;
174  memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6);
175  if (tstamp.t64 <= last_tstamp.t64) {
176  // repeating old timestamp
177  return false;
178  }
179  }
180 
181  // remember last timestamp
182  memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6);
183 
184  // our next timestamp must be at least this timestamp
185  if (tstamp.t64 > signing->timestamp) {
186  signing->timestamp = tstamp.t64;
187  }
188  return true;
189 }
190 
191 
204 MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
205  mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra)
206 {
207  bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
208  bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
209  uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
210  uint8_t header_len = MAVLINK_CORE_HEADER_LEN+1;
211  uint8_t buf[MAVLINK_CORE_HEADER_LEN+1];
212  if (mavlink1) {
214  header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1;
215  } else {
216  msg->magic = MAVLINK_STX;
217  }
218  msg->len = mavlink1?min_length:_mav_trim_payload(_MAV_PAYLOAD(msg), length);
219  msg->sysid = system_id;
220  msg->compid = component_id;
221  msg->incompat_flags = 0;
222  if (signing) {
223  msg->incompat_flags |= MAVLINK_IFLAG_SIGNED;
224  }
225  msg->compat_flags = 0;
226  msg->seq = status->current_tx_seq;
227  status->current_tx_seq = status->current_tx_seq + 1;
228 
229  // form the header as a byte array for the crc
230  buf[0] = msg->magic;
231  buf[1] = msg->len;
232  if (mavlink1) {
233  buf[2] = msg->seq;
234  buf[3] = msg->sysid;
235  buf[4] = msg->compid;
236  buf[5] = msg->msgid & 0xFF;
237  } else {
238  buf[2] = msg->incompat_flags;
239  buf[3] = msg->compat_flags;
240  buf[4] = msg->seq;
241  buf[5] = msg->sysid;
242  buf[6] = msg->compid;
243  buf[7] = msg->msgid & 0xFF;
244  buf[8] = (msg->msgid >> 8) & 0xFF;
245  buf[9] = (msg->msgid >> 16) & 0xFF;
246  }
247 
248  uint16_t checksum = crc_calculate(&buf[1], header_len-1);
249  crc_accumulate_buffer(&checksum, _MAV_PAYLOAD(msg), msg->len);
250  crc_accumulate(crc_extra, &checksum);
251  mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
252  mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
253 
254  msg->checksum = checksum;
255 
256  if (signing) {
258  msg->signature,
259  (const uint8_t *)buf, header_len,
260  (const uint8_t *)_MAV_PAYLOAD(msg), msg->len,
261  (const uint8_t *)_MAV_PAYLOAD(msg)+(uint16_t)msg->len);
262  }
263 
264  return msg->len + header_len + 2 + signature_len;
265 }
266 
267 MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
268  uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
269 {
271  return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra);
272 }
273 
277 MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
278  uint8_t min_length, uint8_t length, uint8_t crc_extra)
279 {
280  return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);
281 }
282 
283 static inline void _mav_parse_error(mavlink_status_t *status)
284 {
285  status->parse_error++;
286 }
287 
288 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
289 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
290 
295  const char *packet,
296  uint8_t min_length, uint8_t length, uint8_t crc_extra)
297 {
298  uint16_t checksum;
299  uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
300  uint8_t ck[2];
302  uint8_t header_len = MAVLINK_CORE_HEADER_LEN;
303  uint8_t signature_len = 0;
304  uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
305  bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
306  bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
307 
308  if (mavlink1) {
309  length = min_length;
310  if (msgid > 255) {
311  // can't send 16 bit messages
312  _mav_parse_error(status);
313  return;
314  }
316  buf[0] = MAVLINK_STX_MAVLINK1;
317  buf[1] = length;
318  buf[2] = status->current_tx_seq;
319  buf[3] = mavlink_system.sysid;
320  buf[4] = mavlink_system.compid;
321  buf[5] = msgid & 0xFF;
322  } else {
323  uint8_t incompat_flags = 0;
324  if (signing) {
325  incompat_flags |= MAVLINK_IFLAG_SIGNED;
326  }
327  length = _mav_trim_payload(packet, length);
328  buf[0] = MAVLINK_STX;
329  buf[1] = length;
330  buf[2] = incompat_flags;
331  buf[3] = 0; // compat_flags
332  buf[4] = status->current_tx_seq;
333  buf[5] = mavlink_system.sysid;
334  buf[6] = mavlink_system.compid;
335  buf[7] = msgid & 0xFF;
336  buf[8] = (msgid >> 8) & 0xFF;
337  buf[9] = (msgid >> 16) & 0xFF;
338  }
339  status->current_tx_seq++;
340  checksum = crc_calculate((const uint8_t*)&buf[1], header_len);
341  crc_accumulate_buffer(&checksum, packet, length);
342  crc_accumulate(crc_extra, &checksum);
343  ck[0] = (uint8_t)(checksum & 0xFF);
344  ck[1] = (uint8_t)(checksum >> 8);
345 
346  if (signing) {
347  // possibly add a signature
348  signature_len = mavlink_sign_packet(status->signing, signature, buf, header_len+1,
349  (const uint8_t *)packet, length, ck);
350  }
351 
352  MAVLINK_START_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
353  _mavlink_send_uart(chan, (const char *)buf, header_len+1);
354  _mavlink_send_uart(chan, packet, length);
355  _mavlink_send_uart(chan, (const char *)ck, 2);
356  if (signature_len != 0) {
357  _mavlink_send_uart(chan, (const char *)signature, signature_len);
358  }
359  MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
360 }
361 
367 MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
368 {
369  uint8_t ck[2];
370 
371  ck[0] = (uint8_t)(msg->checksum & 0xFF);
372  ck[1] = (uint8_t)(msg->checksum >> 8);
373  // XXX use the right sequence here
374 
375  uint8_t header_len;
376  uint8_t signature_len;
377 
378  if (msg->magic == MAVLINK_STX_MAVLINK1) {
379  header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1;
380  signature_len = 0;
381  MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
382  // we can't send the structure directly as it has extra mavlink2 elements in it
383  uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1];
384  buf[0] = msg->magic;
385  buf[1] = msg->len;
386  buf[2] = msg->seq;
387  buf[3] = msg->sysid;
388  buf[4] = msg->compid;
389  buf[5] = msg->msgid & 0xFF;
390  _mavlink_send_uart(chan, (const char*)buf, header_len);
391  } else {
392  header_len = MAVLINK_CORE_HEADER_LEN + 1;
393  signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
394  MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
395  uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1];
396  buf[0] = msg->magic;
397  buf[1] = msg->len;
398  buf[2] = msg->incompat_flags;
399  buf[3] = msg->compat_flags;
400  buf[4] = msg->seq;
401  buf[5] = msg->sysid;
402  buf[6] = msg->compid;
403  buf[7] = msg->msgid & 0xFF;
404  buf[8] = (msg->msgid >> 8) & 0xFF;
405  buf[9] = (msg->msgid >> 16) & 0xFF;
406  _mavlink_send_uart(chan, (const char *)buf, header_len);
407  }
408  _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
409  _mavlink_send_uart(chan, (const char *)ck, 2);
410  if (signature_len != 0) {
411  _mavlink_send_uart(chan, (const char *)msg->signature, MAVLINK_SIGNATURE_BLOCK_LEN);
412  }
413  MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
414 }
415 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
416 
421 {
422  uint8_t signature_len, header_len;
423  uint8_t *ck;
424  uint8_t length = msg->len;
425 
426  if (msg->magic == MAVLINK_STX_MAVLINK1) {
427  signature_len = 0;
429  buf[0] = msg->magic;
430  buf[1] = length;
431  buf[2] = msg->seq;
432  buf[3] = msg->sysid;
433  buf[4] = msg->compid;
434  buf[5] = msg->msgid & 0xFF;
435  memcpy(&buf[6], _MAV_PAYLOAD(msg), msg->len);
436  ck = buf + header_len + 1 + (uint16_t)msg->len;
437  } else {
438  length = _mav_trim_payload(_MAV_PAYLOAD(msg), length);
439  header_len = MAVLINK_CORE_HEADER_LEN;
440  buf[0] = msg->magic;
441  buf[1] = length;
442  buf[2] = msg->incompat_flags;
443  buf[3] = msg->compat_flags;
444  buf[4] = msg->seq;
445  buf[5] = msg->sysid;
446  buf[6] = msg->compid;
447  buf[7] = msg->msgid & 0xFF;
448  buf[8] = (msg->msgid >> 8) & 0xFF;
449  buf[9] = (msg->msgid >> 16) & 0xFF;
450  memcpy(&buf[10], _MAV_PAYLOAD(msg), length);
451  ck = buf + header_len + 1 + (uint16_t)length;
452  signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
453  }
454  ck[0] = (uint8_t)(msg->checksum & 0xFF);
455  ck[1] = (uint8_t)(msg->checksum >> 8);
456  if (signature_len > 0) {
457  memcpy(&ck[2], msg->signature, signature_len);
458  }
459 
460  return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len;
461 }
462 
463 union __mavlink_bitfield {
464  uint8_t uint8;
465  int8_t int8;
466  uint16_t uint16;
467  int16_t int16;
468  uint32_t uint32;
469  int32_t int32;
470 };
471 
472 
474 {
475  uint16_t crcTmp = 0;
476  crc_init(&crcTmp);
477  msg->checksum = crcTmp;
478 }
479 
481 {
482  uint16_t checksum = msg->checksum;
483  crc_accumulate(c, &checksum);
484  msg->checksum = checksum;
485 }
486 
487 /*
488  return the crc_entry value for a msgid
489 */
490 #ifndef MAVLINK_GET_MSG_ENTRY
492 {
493  static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS;
494  /*
495  use a bisection search to find the right entry. A perfect hash may be better
496  Note that this assumes the table is sorted by msgid
497  */
498  uint32_t low=0, high=sizeof(mavlink_message_crcs)/sizeof(mavlink_message_crcs[0]);
499  while (low < high) {
500  uint32_t mid = (low+1+high)/2;
501  if (msgid < mavlink_message_crcs[mid].msgid) {
502  high = mid-1;
503  continue;
504  }
505  if (msgid > mavlink_message_crcs[mid].msgid) {
506  low = mid;
507  continue;
508  }
509  low = mid;
510  break;
511  }
512  if (mavlink_message_crcs[low].msgid != msgid) {
513  // msgid is not in the table
514  return NULL;
515  }
516  return &mavlink_message_crcs[low];
517 }
518 #endif // MAVLINK_GET_MSG_ENTRY
519 
520 /*
521  return the crc_extra value for a message
522 */
524 {
526  return e?e->crc_extra:0;
527 }
528 
529 /*
530  return the min message length
531 */
532 #define MAVLINK_HAVE_MIN_MESSAGE_LENGTH
534 {
536  return e?e->min_msg_len:0;
537 }
538 
539 /*
540  return the max message length (including extensions)
541 */
542 #define MAVLINK_HAVE_MAX_MESSAGE_LENGTH
544 {
546  return e?e->max_msg_len:0;
547 }
548 
564  mavlink_status_t* status,
565  uint8_t c,
566  mavlink_message_t* r_message,
567  mavlink_status_t* r_mavlink_status)
568 {
569  /* Enable this option to check the length of each message.
570  This allows invalid messages to be caught much sooner. Use if the transmission
571  medium is prone to missing (or extra) characters (e.g. a radio that fades in
572  and out). Only use if the channel will only contain messages types listed in
573  the headers.
574  */
575 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
576 #ifndef MAVLINK_MESSAGE_LENGTH
577  static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
578 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
579 #endif
580 #endif
581 
582  int bufferIndex = 0;
583 
585 
586  switch (status->parse_state)
587  {
590  if (c == MAVLINK_STX)
591  {
593  rxmsg->len = 0;
594  rxmsg->magic = c;
596  mavlink_start_checksum(rxmsg);
597  } else if (c == MAVLINK_STX_MAVLINK1)
598  {
600  rxmsg->len = 0;
601  rxmsg->magic = c;
603  mavlink_start_checksum(rxmsg);
604  }
605  break;
606 
608  if (status->msg_received
609 /* Support shorter buffers than the
610  default maximum packet size */
611 #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
613 #endif
614  )
615  {
616  status->buffer_overrun++;
617  _mav_parse_error(status);
618  status->msg_received = 0;
620  }
621  else
622  {
623  // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
624  rxmsg->len = c;
625  status->packet_idx = 0;
626  mavlink_update_checksum(rxmsg, c);
627  if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
628  rxmsg->incompat_flags = 0;
629  rxmsg->compat_flags = 0;
631  } else {
633  }
634  }
635  break;
636 
638  rxmsg->incompat_flags = c;
639  if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) {
640  // message includes an incompatible feature flag
641  _mav_parse_error(status);
642  status->msg_received = 0;
644  break;
645  }
646  mavlink_update_checksum(rxmsg, c);
648  break;
649 
651  rxmsg->compat_flags = c;
652  mavlink_update_checksum(rxmsg, c);
654  break;
655 
657  rxmsg->seq = c;
658  mavlink_update_checksum(rxmsg, c);
660  break;
661 
663  rxmsg->sysid = c;
664  mavlink_update_checksum(rxmsg, c);
666  break;
667 
669  rxmsg->compid = c;
670  mavlink_update_checksum(rxmsg, c);
672  break;
673 
675  rxmsg->msgid = c;
676  mavlink_update_checksum(rxmsg, c);
677  if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
678  if(rxmsg->len > 0){
680  } else {
682  }
683 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
684  if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
685  {
686  _mav_parse_error(status);
688  break;
689  }
690 #endif
691  } else {
693  }
694  break;
695 
697  rxmsg->msgid |= c<<8;
698  mavlink_update_checksum(rxmsg, c);
700  break;
701 
703  rxmsg->msgid |= ((uint32_t)c)<<16;
704  mavlink_update_checksum(rxmsg, c);
705  if(rxmsg->len > 0){
707  } else {
709  }
710 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
711  if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
712  {
713  _mav_parse_error(status);
715  break;
716  }
717 #endif
718  break;
719 
721  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
722  mavlink_update_checksum(rxmsg, c);
723  if (status->packet_idx == rxmsg->len)
724  {
726  }
727  break;
728 
731  uint8_t crc_extra = e?e->crc_extra:0;
732  mavlink_update_checksum(rxmsg, crc_extra);
733  if (c != (rxmsg->checksum & 0xFF)) {
735  } else {
737  }
738  rxmsg->ck[0] = c;
739 
740  // zero-fill the packet to cope with short incoming packets
741  if (e && status->packet_idx < e->max_msg_len) {
742  memset(&_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx], 0, e->max_msg_len - status->packet_idx);
743  }
744  break;
745  }
746 
749  if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) {
750  // got a bad CRC message
752  } else {
753  // Successfully got message
755  }
756  rxmsg->ck[1] = c;
757 
758  if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) {
761 
762  // If the CRC is already wrong, don't overwrite msg_received,
763  // otherwise we can end up with garbage flagged as valid.
764  if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
766  }
767  } else {
768  if (status->signing &&
769  (status->signing->accept_unsigned_callback == NULL ||
770  !status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
771 
772  // If the CRC is already wrong, don't overwrite msg_received.
773  if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
775  }
776  }
778  if (r_message != NULL) {
779  memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
780  }
781  }
782  break;
784  rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c;
785  status->signature_wait--;
786  if (status->signature_wait == 0) {
787  // we have the whole signature, check it is OK
788  bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg);
789  if (!sig_ok &&
790  (status->signing->accept_unsigned_callback &&
791  status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
792  // accepted via application level override
793  sig_ok = true;
794  }
795  if (sig_ok) {
797  } else {
799  }
801  if (r_message !=NULL) {
802  memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
803  }
804  }
805  break;
806  }
807 
808  bufferIndex++;
809  // If a message has been sucessfully decoded, check index
810  if (status->msg_received == MAVLINK_FRAMING_OK)
811  {
812  //while(status->current_seq != rxmsg->seq)
813  //{
814  // status->packet_rx_drop_count++;
815  // status->current_seq++;
816  //}
817  status->current_rx_seq = rxmsg->seq;
818  // Initial condition: If no packet has been received so far, drop count is undefined
819  if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
820  // Count this packet as received
821  status->packet_rx_success_count++;
822  }
823 
824  if (r_message != NULL) {
825  r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg
826  }
827  if (r_mavlink_status != NULL) {
828  r_mavlink_status->parse_state = status->parse_state;
829  r_mavlink_status->packet_idx = status->packet_idx;
830  r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
831  r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
832  r_mavlink_status->packet_rx_drop_count = status->parse_error;
833  r_mavlink_status->flags = status->flags;
834  }
835  status->parse_error = 0;
836 
837  if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
838  /*
839  the CRC came out wrong. We now need to overwrite the
840  msg CRC with the one on the wire so that if the
841  caller decides to forward the message anyway that
842  mavlink_msg_to_send_buffer() won't overwrite the
843  checksum
844  */
845  if (r_message != NULL) {
846  r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8);
847  }
848  }
849 
850  return status->msg_received;
851 }
852 
895 MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
896 {
899  c,
900  r_message,
901  r_mavlink_status);
902 }
903 
907 MAVLINK_HELPER void mavlink_set_proto_version(uint8_t chan, unsigned int version)
908 {
910  if (version > 1) {
912  } else {
914  }
915 }
916 
922 MAVLINK_HELPER unsigned int mavlink_get_proto_version(uint8_t chan)
923 {
925  if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) {
926  return 1;
927  } else {
928  return 2;
929  }
930 }
931 
973 MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
974 {
975  uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);
976  if (msg_received == MAVLINK_FRAMING_BAD_CRC ||
977  msg_received == MAVLINK_FRAMING_BAD_SIGNATURE) {
978  // we got a bad CRC. Treat as a parse failure
981  _mav_parse_error(status);
984  if (c == MAVLINK_STX)
985  {
987  rxmsg->len = 0;
988  mavlink_start_checksum(rxmsg);
989  }
990  return 0;
991  }
992  return msg_received;
993 }
994 
1005 MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
1006 {
1007  uint16_t bits_remain = bits;
1008  // Transform number into network order
1009  int32_t v;
1010  uint8_t i_bit_index, i_byte_index, curr_bits_n;
1011 #if MAVLINK_NEED_BYTE_SWAP
1012  union {
1013  int32_t i;
1014  uint8_t b[4];
1015  } bin, bout;
1016  bin.i = b;
1017  bout.b[0] = bin.b[3];
1018  bout.b[1] = bin.b[2];
1019  bout.b[2] = bin.b[1];
1020  bout.b[3] = bin.b[0];
1021  v = bout.i;
1022 #else
1023  v = b;
1024 #endif
1025 
1026  // buffer in
1027  // 01100000 01000000 00000000 11110001
1028  // buffer out
1029  // 11110001 00000000 01000000 01100000
1030 
1031  // Existing partly filled byte (four free slots)
1032  // 0111xxxx
1033 
1034  // Mask n free bits
1035  // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
1036  // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
1037 
1038  // Shift n bits into the right position
1039  // out = in >> n;
1040 
1041  // Mask and shift bytes
1042  i_bit_index = bit_index;
1043  i_byte_index = packet_index;
1044  if (bit_index > 0)
1045  {
1046  // If bits were available at start, they were available
1047  // in the byte before the current index
1048  i_byte_index--;
1049  }
1050 
1051  // While bits have not been packed yet
1052  while (bits_remain > 0)
1053  {
1054  // Bits still have to be packed
1055  // there can be more than 8 bits, so
1056  // we might have to pack them into more than one byte
1057 
1058  // First pack everything we can into the current 'open' byte
1059  //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
1060  //FIXME
1061  if (bits_remain <= (uint8_t)(8 - i_bit_index))
1062  {
1063  // Enough space
1064  curr_bits_n = (uint8_t)bits_remain;
1065  }
1066  else
1067  {
1068  curr_bits_n = (8 - i_bit_index);
1069  }
1070 
1071  // Pack these n bits into the current byte
1072  // Mask out whatever was at that position with ones (xxx11111)
1073  buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
1074  // Put content to this position, by masking out the non-used part
1075  buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
1076 
1077  // Increment the bit index
1078  i_bit_index += curr_bits_n;
1079 
1080  // Now proceed to the next byte, if necessary
1081  bits_remain -= curr_bits_n;
1082  if (bits_remain > 0)
1083  {
1084  // Offer another 8 bits / one byte
1085  i_byte_index++;
1086  i_bit_index = 0;
1087  }
1088  }
1089 
1090  *r_bit_index = i_bit_index;
1091  // If a partly filled byte is present, mark this as consumed
1092  if (i_bit_index != 7) i_byte_index++;
1093  return i_byte_index - packet_index;
1094 }
1095 
1096 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
1097 
1098 // To make MAVLink work on your MCU, define comm_send_ch() if you wish
1099 // to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
1100 // whole packet at a time
1101 
1102 /*
1103 
1104 #include "mavlink_types.h"
1105 
1106 void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
1107 {
1108  if (chan == MAVLINK_COMM_0)
1109  {
1110  uart0_transmit(ch);
1111  }
1112  if (chan == MAVLINK_COMM_1)
1113  {
1114  uart1_transmit(ch);
1115  }
1116 }
1117  */
1118 
1119 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
1120 {
1121 #ifdef MAVLINK_SEND_UART_BYTES
1122  /* this is the more efficient approach, if the platform
1123  defines it */
1124  MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
1125 #else
1126  /* fallback to one byte at a time */
1127  uint16_t i;
1128  for (i = 0; i < len; i++) {
1129  comm_send_ch(chan, (uint8_t)buf[i]);
1130  }
1131 #endif
1132 }
1133 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
1134 
1135 #ifdef MAVLINK_USE_CXX_NAMESPACE
1136 } // namespace mavlink
1137 #endif
#define MAVLINK_MESSAGE_CRCS
static void crc_init(uint16_t *crcAccum)
Initiliaze the buffer for the X.25 CRC.
#define MAVLINK_MESSAGE_LENGTH(msgid)
Definition: mavnative.c:64
uint8_t min_msg_len
#define MAVLINK_MESSAGE_LENGTHS
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
Definition: testmav.c:135
#define MAVLINK_START_UART_SEND(chan, length)
static uint16_t crc_calculate(const uint8_t *pBuffer, uint16_t length)
Calculates the X.25 checksum on a byte buffer.
#define MAVLINK_END_UART_SEND(chan, length)
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
uint8_t max_msg_len
static mavlink_system_t mavlink_system
Definition: testmav.c:21
uint8_t crc_extra
static void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
Accumulate the X.25 CRC by adding an array of bytes.
static void crc_accumulate(uint8_t data, uint16_t *crcAccum)
Accumulate the X.25 CRC by adding one char at a time.


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:07