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 
99 MAVLINK_HELPER uint8_t _mav_trim_payload(const char *payload, uint8_t length)
100 {
101  while (length > 1 && payload[length-1] == 0) {
102  length--;
103  }
104  return length;
105 }
106 
111  mavlink_signing_streams_t *signing_streams,
112  const mavlink_message_t *msg)
113 {
114  if (signing == NULL) {
115  return true;
116  }
117  const uint8_t *p = (const uint8_t *)&msg->magic;
118  const uint8_t *psig = msg->signature;
119  const uint8_t *incoming_signature = psig+7;
120  mavlink_sha256_ctx ctx;
121  uint8_t signature[6];
122  uint16_t i;
123 
124  mavlink_sha256_init(&ctx);
125  mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
127  mavlink_sha256_update(&ctx, msg->ck, 2);
128  mavlink_sha256_update(&ctx, psig, 1+6);
129  mavlink_sha256_final_48(&ctx, signature);
130  if (memcmp(signature, incoming_signature, 6) != 0) {
131  return false;
132  }
133 
134  // now check timestamp
135  union tstamp {
136  uint64_t t64;
137  uint8_t t8[8];
138  } tstamp;
139  uint8_t link_id = psig[0];
140  tstamp.t64 = 0;
141  memcpy(tstamp.t8, psig+1, 6);
142 
143  if (signing_streams == NULL) {
144  return false;
145  }
146 
147  // find stream
148  for (i=0; i<signing_streams->num_signing_streams; i++) {
149  if (msg->sysid == signing_streams->stream[i].sysid &&
150  msg->compid == signing_streams->stream[i].compid &&
151  link_id == signing_streams->stream[i].link_id) {
152  break;
153  }
154  }
155  if (i == signing_streams->num_signing_streams) {
156  if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) {
157  // over max number of streams
158  return false;
159  }
160  // new stream. Only accept if timestamp is not more than 1 minute old
161  if (tstamp.t64 + 6000*1000UL < signing->timestamp) {
162  return false;
163  }
164  // add new stream
165  signing_streams->stream[i].sysid = msg->sysid;
166  signing_streams->stream[i].compid = msg->compid;
167  signing_streams->stream[i].link_id = link_id;
168  signing_streams->num_signing_streams++;
169  } else {
170  union tstamp last_tstamp;
171  last_tstamp.t64 = 0;
172  memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6);
173  if (tstamp.t64 <= last_tstamp.t64) {
174  // repeating old timestamp
175  return false;
176  }
177  }
178 
179  // remember last timestamp
180  memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6);
181 
182  // our next timestamp must be at least this timestamp
183  if (tstamp.t64 > signing->timestamp) {
184  signing->timestamp = tstamp.t64;
185  }
186  return true;
187 }
188 
189 
202 MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
203  mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra)
204 {
205  bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
206  bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
207  uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
208  uint8_t header_len = MAVLINK_CORE_HEADER_LEN+1;
209  uint8_t buf[MAVLINK_CORE_HEADER_LEN+1];
210  if (mavlink1) {
212  header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1;
213  } else {
214  msg->magic = MAVLINK_STX;
215  }
216  msg->len = mavlink1?min_length:_mav_trim_payload(_MAV_PAYLOAD(msg), length);
217  msg->sysid = system_id;
218  msg->compid = component_id;
219  msg->incompat_flags = 0;
220  if (signing) {
221  msg->incompat_flags |= MAVLINK_IFLAG_SIGNED;
222  }
223  msg->compat_flags = 0;
224  msg->seq = status->current_tx_seq;
225  status->current_tx_seq = status->current_tx_seq + 1;
226 
227  // form the header as a byte array for the crc
228  buf[0] = msg->magic;
229  buf[1] = msg->len;
230  if (mavlink1) {
231  buf[2] = msg->seq;
232  buf[3] = msg->sysid;
233  buf[4] = msg->compid;
234  buf[5] = msg->msgid & 0xFF;
235  } else {
236  buf[2] = msg->incompat_flags;
237  buf[3] = msg->compat_flags;
238  buf[4] = msg->seq;
239  buf[5] = msg->sysid;
240  buf[6] = msg->compid;
241  buf[7] = msg->msgid & 0xFF;
242  buf[8] = (msg->msgid >> 8) & 0xFF;
243  buf[9] = (msg->msgid >> 16) & 0xFF;
244  }
245 
246  uint16_t checksum = crc_calculate(&buf[1], header_len-1);
247  crc_accumulate_buffer(&checksum, _MAV_PAYLOAD(msg), msg->len);
248  crc_accumulate(crc_extra, &checksum);
249  mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
250  mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
251 
252  msg->checksum = checksum;
253 
254  if (signing) {
256  msg->signature,
257  (const uint8_t *)buf, header_len,
258  (const uint8_t *)_MAV_PAYLOAD(msg), msg->len,
259  (const uint8_t *)_MAV_PAYLOAD(msg)+(uint16_t)msg->len);
260  }
261 
262  return msg->len + header_len + 2 + signature_len;
263 }
264 
265 MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
266  uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
267 {
269  return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra);
270 }
271 
275 MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
276  uint8_t min_length, uint8_t length, uint8_t crc_extra)
277 {
278  return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);
279 }
280 
281 static inline void _mav_parse_error(mavlink_status_t *status)
282 {
283  status->parse_error++;
284 }
285 
286 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
287 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
288 
293  const char *packet,
294  uint8_t min_length, uint8_t length, uint8_t crc_extra)
295 {
296  uint16_t checksum;
297  uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
298  uint8_t ck[2];
300  uint8_t header_len = MAVLINK_CORE_HEADER_LEN;
301  uint8_t signature_len = 0;
302  uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
303  bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
304  bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
305 
306  if (mavlink1) {
307  length = min_length;
308  if (msgid > 255) {
309  // can't send 16 bit messages
310  _mav_parse_error(status);
311  return;
312  }
314  buf[0] = MAVLINK_STX_MAVLINK1;
315  buf[1] = length;
316  buf[2] = status->current_tx_seq;
317  buf[3] = mavlink_system.sysid;
318  buf[4] = mavlink_system.compid;
319  buf[5] = msgid & 0xFF;
320  } else {
321  uint8_t incompat_flags = 0;
322  if (signing) {
323  incompat_flags |= MAVLINK_IFLAG_SIGNED;
324  }
325  length = _mav_trim_payload(packet, length);
326  buf[0] = MAVLINK_STX;
327  buf[1] = length;
328  buf[2] = incompat_flags;
329  buf[3] = 0; // compat_flags
330  buf[4] = status->current_tx_seq;
331  buf[5] = mavlink_system.sysid;
332  buf[6] = mavlink_system.compid;
333  buf[7] = msgid & 0xFF;
334  buf[8] = (msgid >> 8) & 0xFF;
335  buf[9] = (msgid >> 16) & 0xFF;
336  }
337  status->current_tx_seq++;
338  checksum = crc_calculate((const uint8_t*)&buf[1], header_len);
339  crc_accumulate_buffer(&checksum, packet, length);
340  crc_accumulate(crc_extra, &checksum);
341  ck[0] = (uint8_t)(checksum & 0xFF);
342  ck[1] = (uint8_t)(checksum >> 8);
343 
344  if (signing) {
345  // possibly add a signature
346  signature_len = mavlink_sign_packet(status->signing, signature, buf, header_len+1,
347  (const uint8_t *)packet, length, ck);
348  }
349 
350  MAVLINK_START_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
351  _mavlink_send_uart(chan, (const char *)buf, header_len+1);
352  _mavlink_send_uart(chan, packet, length);
353  _mavlink_send_uart(chan, (const char *)ck, 2);
354  if (signature_len != 0) {
355  _mavlink_send_uart(chan, (const char *)signature, signature_len);
356  }
357  MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
358 }
359 
365 MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
366 {
367  uint8_t ck[2];
368 
369  ck[0] = (uint8_t)(msg->checksum & 0xFF);
370  ck[1] = (uint8_t)(msg->checksum >> 8);
371  // XXX use the right sequence here
372 
373  uint8_t header_len;
374  uint8_t signature_len;
375 
376  if (msg->magic == MAVLINK_STX_MAVLINK1) {
377  header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1;
378  signature_len = 0;
379  MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
380  // we can't send the structure directly as it has extra mavlink2 elements in it
381  uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1];
382  buf[0] = msg->magic;
383  buf[1] = msg->len;
384  buf[2] = msg->seq;
385  buf[3] = msg->sysid;
386  buf[4] = msg->compid;
387  buf[5] = msg->msgid & 0xFF;
388  _mavlink_send_uart(chan, (const char*)buf, header_len);
389  } else {
390  header_len = MAVLINK_CORE_HEADER_LEN + 1;
391  signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
392  MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
393  uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1];
394  buf[0] = msg->magic;
395  buf[1] = msg->len;
396  buf[2] = msg->incompat_flags;
397  buf[3] = msg->compat_flags;
398  buf[4] = msg->seq;
399  buf[5] = msg->sysid;
400  buf[6] = msg->compid;
401  buf[7] = msg->msgid & 0xFF;
402  buf[8] = (msg->msgid >> 8) & 0xFF;
403  buf[9] = (msg->msgid >> 16) & 0xFF;
404  _mavlink_send_uart(chan, (const char *)buf, header_len);
405  }
406  _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
407  _mavlink_send_uart(chan, (const char *)ck, 2);
408  if (signature_len != 0) {
409  _mavlink_send_uart(chan, (const char *)msg->signature, MAVLINK_SIGNATURE_BLOCK_LEN);
410  }
411  MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
412 }
413 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
414 
419 {
420  uint8_t signature_len, header_len;
421  uint8_t *ck;
422  uint8_t length = msg->len;
423 
424  if (msg->magic == MAVLINK_STX_MAVLINK1) {
425  signature_len = 0;
427  buf[0] = msg->magic;
428  buf[1] = length;
429  buf[2] = msg->seq;
430  buf[3] = msg->sysid;
431  buf[4] = msg->compid;
432  buf[5] = msg->msgid & 0xFF;
433  memcpy(&buf[6], _MAV_PAYLOAD(msg), msg->len);
434  ck = buf + header_len + 1 + (uint16_t)msg->len;
435  } else {
436  length = _mav_trim_payload(_MAV_PAYLOAD(msg), length);
437  header_len = MAVLINK_CORE_HEADER_LEN;
438  buf[0] = msg->magic;
439  buf[1] = length;
440  buf[2] = msg->incompat_flags;
441  buf[3] = msg->compat_flags;
442  buf[4] = msg->seq;
443  buf[5] = msg->sysid;
444  buf[6] = msg->compid;
445  buf[7] = msg->msgid & 0xFF;
446  buf[8] = (msg->msgid >> 8) & 0xFF;
447  buf[9] = (msg->msgid >> 16) & 0xFF;
448  memcpy(&buf[10], _MAV_PAYLOAD(msg), length);
449  ck = buf + header_len + 1 + (uint16_t)length;
450  signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
451  }
452  ck[0] = (uint8_t)(msg->checksum & 0xFF);
453  ck[1] = (uint8_t)(msg->checksum >> 8);
454  if (signature_len > 0) {
455  memcpy(&ck[2], msg->signature, signature_len);
456  }
457 
458  return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len;
459 }
460 
461 union __mavlink_bitfield {
462  uint8_t uint8;
463  int8_t int8;
464  uint16_t uint16;
465  int16_t int16;
466  uint32_t uint32;
467  int32_t int32;
468 };
469 
470 
472 {
473  uint16_t crcTmp = 0;
474  crc_init(&crcTmp);
475  msg->checksum = crcTmp;
476 }
477 
479 {
480  uint16_t checksum = msg->checksum;
481  crc_accumulate(c, &checksum);
482  msg->checksum = checksum;
483 }
484 
485 /*
486  return the crc_entry value for a msgid
487 */
488 #ifndef MAVLINK_GET_MSG_ENTRY
490 {
491  static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS;
492  /*
493  use a bisection search to find the right entry. A perfect hash may be better
494  Note that this assumes the table is sorted by msgid
495  */
496  uint32_t low=0, high=sizeof(mavlink_message_crcs)/sizeof(mavlink_message_crcs[0]);
497  while (low < high) {
498  uint32_t mid = (low+1+high)/2;
499  if (msgid < mavlink_message_crcs[mid].msgid) {
500  high = mid-1;
501  continue;
502  }
503  if (msgid > mavlink_message_crcs[mid].msgid) {
504  low = mid;
505  continue;
506  }
507  low = mid;
508  break;
509  }
510  if (mavlink_message_crcs[low].msgid != msgid) {
511  // msgid is not in the table
512  return NULL;
513  }
514  return &mavlink_message_crcs[low];
515 }
516 #endif // MAVLINK_GET_MSG_ENTRY
517 
518 /*
519  return the crc_extra value for a message
520 */
522 {
524  return e?e->crc_extra:0;
525 }
526 
527 /*
528  return the expected message length
529 */
530 #define MAVLINK_HAVE_EXPECTED_MESSAGE_LENGTH
532 {
534  return e?e->msg_len:0;
535 }
536 
552  mavlink_status_t* status,
553  uint8_t c,
554  mavlink_message_t* r_message,
555  mavlink_status_t* r_mavlink_status)
556 {
557  /* Enable this option to check the length of each message.
558  This allows invalid messages to be caught much sooner. Use if the transmission
559  medium is prone to missing (or extra) characters (e.g. a radio that fades in
560  and out). Only use if the channel will only contain messages types listed in
561  the headers.
562  */
563 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
564 #ifndef MAVLINK_MESSAGE_LENGTH
565  static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
566 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
567 #endif
568 #endif
569 
570  int bufferIndex = 0;
571 
573 
574  switch (status->parse_state)
575  {
578  if (c == MAVLINK_STX)
579  {
581  rxmsg->len = 0;
582  rxmsg->magic = c;
584  mavlink_start_checksum(rxmsg);
585  } else if (c == MAVLINK_STX_MAVLINK1)
586  {
588  rxmsg->len = 0;
589  rxmsg->magic = c;
591  mavlink_start_checksum(rxmsg);
592  }
593  break;
594 
596  if (status->msg_received
597 /* Support shorter buffers than the
598  default maximum packet size */
599 #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
601 #endif
602  )
603  {
604  status->buffer_overrun++;
605  _mav_parse_error(status);
606  status->msg_received = 0;
608  }
609  else
610  {
611  // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
612  rxmsg->len = c;
613  status->packet_idx = 0;
614  mavlink_update_checksum(rxmsg, c);
615  if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
616  rxmsg->incompat_flags = 0;
617  rxmsg->compat_flags = 0;
619  } else {
621  }
622  }
623  break;
624 
626  rxmsg->incompat_flags = c;
627  if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) {
628  // message includes an incompatible feature flag
629  _mav_parse_error(status);
630  status->msg_received = 0;
632  break;
633  }
634  mavlink_update_checksum(rxmsg, c);
636  break;
637 
639  rxmsg->compat_flags = c;
640  mavlink_update_checksum(rxmsg, c);
642  break;
643 
645  rxmsg->seq = c;
646  mavlink_update_checksum(rxmsg, c);
648  break;
649 
651  rxmsg->sysid = c;
652  mavlink_update_checksum(rxmsg, c);
654  break;
655 
657  rxmsg->compid = c;
658  mavlink_update_checksum(rxmsg, c);
660  break;
661 
663  rxmsg->msgid = c;
664  mavlink_update_checksum(rxmsg, c);
665  if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
666  if(rxmsg->len > 0){
668  } else {
670  }
671 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
672  if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
673  {
674  _mav_parse_error(status);
676  break;
677  }
678 #endif
679  } else {
681  }
682  break;
683 
685  rxmsg->msgid |= c<<8;
686  mavlink_update_checksum(rxmsg, c);
688  break;
689 
691  rxmsg->msgid |= ((uint32_t)c)<<16;
692  mavlink_update_checksum(rxmsg, c);
693  if(rxmsg->len > 0){
695  } else {
697  }
698 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
699  if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
700  {
701  _mav_parse_error(status);
703  break;
704  }
705 #endif
706  break;
707 
709  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
710  mavlink_update_checksum(rxmsg, c);
711  if (status->packet_idx == rxmsg->len)
712  {
714  }
715  break;
716 
719  uint8_t crc_extra = e?e->crc_extra:0;
720  mavlink_update_checksum(rxmsg, crc_extra);
721  if (c != (rxmsg->checksum & 0xFF)) {
723  } else {
725  }
726  rxmsg->ck[0] = c;
727 
728  // zero-fill the packet to cope with short incoming packets
729  if (e && status->packet_idx < e->msg_len) {
730  memset(&_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx], 0, e->msg_len - status->packet_idx);
731  }
732  break;
733  }
734 
737  if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) {
738  // got a bad CRC message
740  } else {
741  // Successfully got message
743  }
744  rxmsg->ck[1] = c;
745 
746  if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) {
749 
750  // If the CRC is already wrong, don't overwrite msg_received,
751  // otherwise we can end up with garbage flagged as valid.
752  if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
754  }
755  } else {
756  if (status->signing &&
757  (status->signing->accept_unsigned_callback == NULL ||
758  !status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
759 
760  // If the CRC is already wrong, don't overwrite msg_received.
761  if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
763  }
764  }
766  memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
767  }
768  break;
770  rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c;
771  status->signature_wait--;
772  if (status->signature_wait == 0) {
773  // we have the whole signature, check it is OK
774  bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg);
775  if (!sig_ok &&
776  (status->signing->accept_unsigned_callback &&
777  status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
778  // accepted via application level override
779  sig_ok = true;
780  }
781  if (sig_ok) {
783  } else {
785  }
787  memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
788  }
789  break;
790  }
791 
792  bufferIndex++;
793  // If a message has been sucessfully decoded, check index
794  if (status->msg_received == MAVLINK_FRAMING_OK)
795  {
796  //while(status->current_seq != rxmsg->seq)
797  //{
798  // status->packet_rx_drop_count++;
799  // status->current_seq++;
800  //}
801  status->current_rx_seq = rxmsg->seq;
802  // Initial condition: If no packet has been received so far, drop count is undefined
803  if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
804  // Count this packet as received
805  status->packet_rx_success_count++;
806  }
807 
808  if (NULL != r_message) {
809  r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg
810  }
811  if (NULL != r_mavlink_status) {
812  r_mavlink_status->parse_state = status->parse_state;
813  r_mavlink_status->packet_idx = status->packet_idx;
814  r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
815  r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
816  r_mavlink_status->packet_rx_drop_count = status->parse_error;
817  r_mavlink_status->flags = status->flags;
818  }
819  status->parse_error = 0;
820 
821  if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
822  /*
823  the CRC came out wrong. We now need to overwrite the
824  msg CRC with the one on the wire so that if the
825  caller decides to forward the message anyway that
826  mavlink_msg_to_send_buffer() won't overwrite the
827  checksum
828  */
829  if (NULL != r_message) {
830  r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8);
831  }
832  }
833 
834  return status->msg_received;
835 }
836 
879 MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
880 {
883  c,
884  r_message,
885  r_mavlink_status);
886 }
887 
891 MAVLINK_HELPER void mavlink_set_proto_version(uint8_t chan, unsigned int version)
892 {
894  if (version > 1) {
896  } else {
898  }
899 }
900 
906 MAVLINK_HELPER unsigned int mavlink_get_proto_version(uint8_t chan)
907 {
909  if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) {
910  return 1;
911  } else {
912  return 2;
913  }
914 }
915 
957 MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
958 {
959  uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);
960  if (msg_received == MAVLINK_FRAMING_BAD_CRC ||
961  msg_received == MAVLINK_FRAMING_BAD_SIGNATURE) {
962  // we got a bad CRC. Treat as a parse failure
965  _mav_parse_error(status);
968  if (c == MAVLINK_STX)
969  {
971  rxmsg->len = 0;
972  mavlink_start_checksum(rxmsg);
973  }
974  return 0;
975  }
976  return msg_received;
977 }
978 
989 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)
990 {
991  uint16_t bits_remain = bits;
992  // Transform number into network order
993  int32_t v;
994  uint8_t i_bit_index, i_byte_index, curr_bits_n;
995 #if MAVLINK_NEED_BYTE_SWAP
996  union {
997  int32_t i;
998  uint8_t b[4];
999  } bin, bout;
1000  bin.i = b;
1001  bout.b[0] = bin.b[3];
1002  bout.b[1] = bin.b[2];
1003  bout.b[2] = bin.b[1];
1004  bout.b[3] = bin.b[0];
1005  v = bout.i;
1006 #else
1007  v = b;
1008 #endif
1009 
1010  // buffer in
1011  // 01100000 01000000 00000000 11110001
1012  // buffer out
1013  // 11110001 00000000 01000000 01100000
1014 
1015  // Existing partly filled byte (four free slots)
1016  // 0111xxxx
1017 
1018  // Mask n free bits
1019  // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
1020  // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
1021 
1022  // Shift n bits into the right position
1023  // out = in >> n;
1024 
1025  // Mask and shift bytes
1026  i_bit_index = bit_index;
1027  i_byte_index = packet_index;
1028  if (bit_index > 0)
1029  {
1030  // If bits were available at start, they were available
1031  // in the byte before the current index
1032  i_byte_index--;
1033  }
1034 
1035  // While bits have not been packed yet
1036  while (bits_remain > 0)
1037  {
1038  // Bits still have to be packed
1039  // there can be more than 8 bits, so
1040  // we might have to pack them into more than one byte
1041 
1042  // First pack everything we can into the current 'open' byte
1043  //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
1044  //FIXME
1045  if (bits_remain <= (uint8_t)(8 - i_bit_index))
1046  {
1047  // Enough space
1048  curr_bits_n = (uint8_t)bits_remain;
1049  }
1050  else
1051  {
1052  curr_bits_n = (8 - i_bit_index);
1053  }
1054 
1055  // Pack these n bits into the current byte
1056  // Mask out whatever was at that position with ones (xxx11111)
1057  buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
1058  // Put content to this position, by masking out the non-used part
1059  buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
1060 
1061  // Increment the bit index
1062  i_bit_index += curr_bits_n;
1063 
1064  // Now proceed to the next byte, if necessary
1065  bits_remain -= curr_bits_n;
1066  if (bits_remain > 0)
1067  {
1068  // Offer another 8 bits / one byte
1069  i_byte_index++;
1070  i_bit_index = 0;
1071  }
1072  }
1073 
1074  *r_bit_index = i_bit_index;
1075  // If a partly filled byte is present, mark this as consumed
1076  if (i_bit_index != 7) i_byte_index++;
1077  return i_byte_index - packet_index;
1078 }
1079 
1080 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
1081 
1082 // To make MAVLink work on your MCU, define comm_send_ch() if you wish
1083 // to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
1084 // whole packet at a time
1085 
1086 /*
1087 
1088 #include "mavlink_types.h"
1089 
1090 void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
1091 {
1092  if (chan == MAVLINK_COMM_0)
1093  {
1094  uart0_transmit(ch);
1095  }
1096  if (chan == MAVLINK_COMM_1)
1097  {
1098  uart1_transmit(ch);
1099  }
1100 }
1101  */
1102 
1103 MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
1104 {
1105 #ifdef MAVLINK_SEND_UART_BYTES
1106  /* this is the more efficient approach, if the platform
1107  defines it */
1108  MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
1109 #else
1110  /* fallback to one byte at a time */
1111  uint16_t i;
1112  for (i = 0; i < len; i++) {
1113  comm_send_ch(chan, (uint8_t)buf[i]);
1114  }
1115 #endif
1116 }
1117 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
1118 
1119 #ifdef MAVLINK_USE_CXX_NAMESPACE
1120 } // namespace mavlink
1121 #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
#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)
static mavlink_system_t mavlink_system
Definition: testmav.c:21
uint8_t msg_len
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 Apr 7 2019 02:06:02