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