-
Notifications
You must be signed in to change notification settings - Fork 0
/
mavlink_helpers.h
1152 lines (1056 loc) · 36.5 KB
/
mavlink_helpers.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#pragma once
#include "string.h"
#include "checksum.h"
#include "mavlink_types.h"
#include "mavlink_conversions.h"
#include <stdio.h>
#ifndef MAVLINK_HELPER
#define MAVLINK_HELPER
#endif
#include "mavlink_sha256.h"
#ifdef MAVLINK_USE_CXX_NAMESPACE
namespace mavlink {
#endif
/*
* Internal function to give access to the channel status for each channel
*/
#ifndef MAVLINK_GET_CHANNEL_STATUS
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
#ifdef MAVLINK_EXTERNAL_RX_STATUS
// No m_mavlink_status array defined in function,
// has to be defined externally
#else
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
#endif
return &m_mavlink_status[chan];
}
#endif
/*
* Internal function to give access to the channel buffer for each channel
*/
#ifndef MAVLINK_GET_CHANNEL_BUFFER
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
#ifdef MAVLINK_EXTERNAL_RX_BUFFER
// No m_mavlink_buffer array defined in function,
// has to be defined externally
#else
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
#endif
return &m_mavlink_buffer[chan];
}
#endif // MAVLINK_GET_CHANNEL_BUFFER
/* Enable this option to check the length of each message.
This allows invalid messages to be caught much sooner. Use if the transmission
medium is prone to missing (or extra) characters (e.g. a radio that fades in
and out). Only use if the channel will only contain messages types listed in
the headers.
*/
//#define MAVLINK_CHECK_MESSAGE_LENGTH
/**
* @brief Reset the status of a channel.
*/
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
}
#ifndef MAVLINK_NO_SIGN_PACKET
/**
* @brief create a signature block for a packet
*/
MAVLINK_HELPER uint8_t mavlink_sign_packet(mavlink_signing_t *signing,
uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN],
const uint8_t *header, uint8_t header_len,
const uint8_t *packet, uint8_t packet_len,
const uint8_t crc[2])
{
mavlink_sha256_ctx ctx;
union {
uint64_t t64;
uint8_t t8[8];
} tstamp;
if (signing == NULL || !(signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
return 0;
}
signature[0] = signing->link_id;
tstamp.t64 = signing->timestamp;
memcpy(&signature[1], tstamp.t8, 6);
signing->timestamp++;
mavlink_sha256_init(&ctx);
mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
mavlink_sha256_update(&ctx, header, header_len);
mavlink_sha256_update(&ctx, packet, packet_len);
mavlink_sha256_update(&ctx, crc, 2);
mavlink_sha256_update(&ctx, signature, 7);
mavlink_sha256_final_48(&ctx, &signature[7]);
return MAVLINK_SIGNATURE_BLOCK_LEN;
}
#endif
/**
* @brief Trim payload of any trailing zero-populated bytes (MAVLink 2 only).
*
* @param payload Serialised payload buffer.
* @param length Length of full-width payload buffer.
* @return Length of payload after zero-filled bytes are trimmed.
*/
MAVLINK_HELPER uint8_t _mav_trim_payload(const char *payload, uint8_t length)
{
while (length > 1 && payload[length-1] == 0) {
length--;
}
return length;
}
#ifndef MAVLINK_NO_SIGNATURE_CHECK
/**
* @brief check a signature block for a packet
*/
MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
mavlink_signing_streams_t *signing_streams,
const mavlink_message_t *msg)
{
if (signing == NULL) {
return true;
}
const uint8_t *p = (const uint8_t *)&msg->magic;
const uint8_t *psig = msg->signature;
const uint8_t *incoming_signature = psig+7;
mavlink_sha256_ctx ctx;
uint8_t signature[6];
uint16_t i;
mavlink_sha256_init(&ctx);
mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
mavlink_sha256_update(&ctx, p, MAVLINK_NUM_HEADER_BYTES);
mavlink_sha256_update(&ctx, _MAV_PAYLOAD(msg), msg->len);
mavlink_sha256_update(&ctx, msg->ck, 2);
mavlink_sha256_update(&ctx, psig, 1+6);
mavlink_sha256_final_48(&ctx, signature);
if (memcmp(signature, incoming_signature, 6) != 0) {
signing->last_status = MAVLINK_SIGNING_STATUS_BAD_SIGNATURE;
return false;
}
// now check timestamp
union tstamp {
uint64_t t64;
uint8_t t8[8];
} tstamp;
uint8_t link_id = psig[0];
tstamp.t64 = 0;
memcpy(tstamp.t8, psig+1, 6);
if (signing_streams == NULL) {
signing->last_status = MAVLINK_SIGNING_STATUS_NO_STREAMS;
return false;
}
// find stream
for (i=0; i<signing_streams->num_signing_streams; i++) {
if (msg->sysid == signing_streams->stream[i].sysid &&
msg->compid == signing_streams->stream[i].compid &&
link_id == signing_streams->stream[i].link_id) {
break;
}
}
if (i == signing_streams->num_signing_streams) {
if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) {
// over max number of streams
signing->last_status = MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS;
return false;
}
// new stream. Only accept if timestamp is not more than 1 minute old
if (tstamp.t64 + 6000*1000UL < signing->timestamp) {
signing->last_status = MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP;
return false;
}
// add new stream
signing_streams->stream[i].sysid = msg->sysid;
signing_streams->stream[i].compid = msg->compid;
signing_streams->stream[i].link_id = link_id;
signing_streams->num_signing_streams++;
} else {
union tstamp last_tstamp;
last_tstamp.t64 = 0;
memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6);
if (tstamp.t64 <= last_tstamp.t64) {
// repeating old timestamp
signing->last_status = MAVLINK_SIGNING_STATUS_REPLAY;
return false;
}
}
// remember last timestamp
memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6);
// our next timestamp must be at least this timestamp
if (tstamp.t64 > signing->timestamp) {
signing->timestamp = tstamp.t64;
}
signing->last_status = MAVLINK_SIGNING_STATUS_OK;
return true;
}
#endif
/**
* @brief Finalize a MAVLink message with channel assignment
*
* This function calculates the checksum and sets length and aircraft id correctly.
* It assumes that the message id and the payload are already correctly set. This function
* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
*
* @param msg Message to finalize
* @param system_id Id of the sending (this) system, 1-127
* @param length Message length
*/
MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra)
{
bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
#ifndef MAVLINK_NO_SIGN_PACKET
bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
#else
bool signing = false;
#endif
uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
uint8_t header_len = MAVLINK_CORE_HEADER_LEN+1;
uint8_t buf[MAVLINK_CORE_HEADER_LEN+1];
if (mavlink1) {
msg->magic = MAVLINK_STX_MAVLINK1;
header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1;
} else {
msg->magic = MAVLINK_STX;
}
msg->len = mavlink1?min_length:_mav_trim_payload(_MAV_PAYLOAD(msg), length);
msg->sysid = system_id;
msg->compid = component_id;
msg->incompat_flags = 0;
if (signing) {
msg->incompat_flags |= MAVLINK_IFLAG_SIGNED;
}
msg->compat_flags = 0;
msg->seq = status->current_tx_seq;
status->current_tx_seq = status->current_tx_seq + 1;
// form the header as a byte array for the crc
buf[0] = msg->magic;
buf[1] = msg->len;
if (mavlink1) {
buf[2] = msg->seq;
buf[3] = msg->sysid;
buf[4] = msg->compid;
buf[5] = msg->msgid & 0xFF;
} else {
buf[2] = msg->incompat_flags;
buf[3] = msg->compat_flags;
buf[4] = msg->seq;
buf[5] = msg->sysid;
buf[6] = msg->compid;
buf[7] = msg->msgid & 0xFF;
buf[8] = (msg->msgid >> 8) & 0xFF;
buf[9] = (msg->msgid >> 16) & 0xFF;
}
uint16_t checksum = crc_calculate(&buf[1], header_len-1);
crc_accumulate_buffer(&checksum, _MAV_PAYLOAD(msg), msg->len);
crc_accumulate(crc_extra, &checksum);
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
msg->checksum = checksum;
#ifndef MAVLINK_NO_SIGN_PACKET
if (signing) {
mavlink_sign_packet(status->signing,
msg->signature,
(const uint8_t *)buf, header_len,
(const uint8_t *)_MAV_PAYLOAD(msg), msg->len,
(const uint8_t *)_MAV_PAYLOAD(msg)+(uint16_t)msg->len);
}
#endif
return msg->len + header_len + 2 + signature_len;
}
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra);
}
/**
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
*/
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t min_length, uint8_t length, uint8_t crc_extra)
{
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);
}
static inline void _mav_parse_error(mavlink_status_t *status)
{
status->parse_error++;
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
/**
* @brief Finalize a MAVLink message with channel assignment and send
*/
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid,
const char *packet,
uint8_t min_length, uint8_t length, uint8_t crc_extra)
{
uint16_t checksum;
uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
uint8_t ck[2];
mavlink_status_t *status = mavlink_get_channel_status(chan);
uint8_t header_len = MAVLINK_CORE_HEADER_LEN;
uint8_t signature_len = 0;
uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
if (mavlink1) {
length = min_length;
if (msgid > 255) {
// can't send 16 bit messages
_mav_parse_error(status);
return;
}
header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN;
buf[0] = MAVLINK_STX_MAVLINK1;
buf[1] = length;
buf[2] = status->current_tx_seq;
buf[3] = mavlink_system.sysid;
buf[4] = mavlink_system.compid;
buf[5] = msgid & 0xFF;
} else {
uint8_t incompat_flags = 0;
if (signing) {
incompat_flags |= MAVLINK_IFLAG_SIGNED;
}
length = _mav_trim_payload(packet, length);
buf[0] = MAVLINK_STX;
buf[1] = length;
buf[2] = incompat_flags;
buf[3] = 0; // compat_flags
buf[4] = status->current_tx_seq;
buf[5] = mavlink_system.sysid;
buf[6] = mavlink_system.compid;
buf[7] = msgid & 0xFF;
buf[8] = (msgid >> 8) & 0xFF;
buf[9] = (msgid >> 16) & 0xFF;
}
status->current_tx_seq++;
checksum = crc_calculate((const uint8_t*)&buf[1], header_len);
crc_accumulate_buffer(&checksum, packet, length);
crc_accumulate(crc_extra, &checksum);
ck[0] = (uint8_t)(checksum & 0xFF);
ck[1] = (uint8_t)(checksum >> 8);
if (signing) {
// possibly add a signature
signature_len = mavlink_sign_packet(status->signing, signature, buf, header_len+1,
(const uint8_t *)packet, length, ck);
}
MAVLINK_START_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
_mavlink_send_uart(chan, (const char *)buf, header_len+1);
_mavlink_send_uart(chan, packet, length);
_mavlink_send_uart(chan, (const char *)ck, 2);
if (signature_len != 0) {
_mavlink_send_uart(chan, (const char *)signature, signature_len);
}
MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
}
/**
* @brief re-send a message over a uart channel
* this is more stack efficient than re-marshalling the message
* If the message is signed then the original signature is also sent
*/
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
{
uint8_t ck[2];
ck[0] = (uint8_t)(msg->checksum & 0xFF);
ck[1] = (uint8_t)(msg->checksum >> 8);
// XXX use the right sequence here
uint8_t header_len;
uint8_t signature_len;
if (msg->magic == MAVLINK_STX_MAVLINK1) {
header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1;
signature_len = 0;
MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
// we can't send the structure directly as it has extra mavlink2 elements in it
uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1];
buf[0] = msg->magic;
buf[1] = msg->len;
buf[2] = msg->seq;
buf[3] = msg->sysid;
buf[4] = msg->compid;
buf[5] = msg->msgid & 0xFF;
_mavlink_send_uart(chan, (const char*)buf, header_len);
} else {
header_len = MAVLINK_CORE_HEADER_LEN + 1;
signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1];
buf[0] = msg->magic;
buf[1] = msg->len;
buf[2] = msg->incompat_flags;
buf[3] = msg->compat_flags;
buf[4] = msg->seq;
buf[5] = msg->sysid;
buf[6] = msg->compid;
buf[7] = msg->msgid & 0xFF;
buf[8] = (msg->msgid >> 8) & 0xFF;
buf[9] = (msg->msgid >> 16) & 0xFF;
_mavlink_send_uart(chan, (const char *)buf, header_len);
}
_mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
_mavlink_send_uart(chan, (const char *)ck, 2);
if (signature_len != 0) {
_mavlink_send_uart(chan, (const char *)msg->signature, MAVLINK_SIGNATURE_BLOCK_LEN);
}
MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a message to send it over a serial byte stream
*/
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buf, const mavlink_message_t *msg)
{
uint8_t signature_len, header_len;
uint8_t *ck;
uint8_t length = msg->len;
if (msg->magic == MAVLINK_STX_MAVLINK1) {
signature_len = 0;
header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN;
buf[0] = msg->magic;
buf[1] = length;
buf[2] = msg->seq;
buf[3] = msg->sysid;
buf[4] = msg->compid;
buf[5] = msg->msgid & 0xFF;
memcpy(&buf[6], _MAV_PAYLOAD(msg), msg->len);
ck = buf + header_len + 1 + (uint16_t)msg->len;
} else {
length = _mav_trim_payload(_MAV_PAYLOAD(msg), length);
header_len = MAVLINK_CORE_HEADER_LEN;
buf[0] = msg->magic;
buf[1] = length;
buf[2] = msg->incompat_flags;
buf[3] = msg->compat_flags;
buf[4] = msg->seq;
buf[5] = msg->sysid;
buf[6] = msg->compid;
buf[7] = msg->msgid & 0xFF;
buf[8] = (msg->msgid >> 8) & 0xFF;
buf[9] = (msg->msgid >> 16) & 0xFF;
memcpy(&buf[10], _MAV_PAYLOAD(msg), length);
ck = buf + header_len + 1 + (uint16_t)length;
signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
}
ck[0] = (uint8_t)(msg->checksum & 0xFF);
ck[1] = (uint8_t)(msg->checksum >> 8);
if (signature_len > 0) {
memcpy(&ck[2], msg->signature, signature_len);
}
return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len;
}
union __mavlink_bitfield {
uint8_t uint8;
int8_t int8;
uint16_t uint16;
int16_t int16;
uint32_t uint32;
int32_t int32;
};
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
{
uint16_t crcTmp = 0;
crc_init(&crcTmp);
msg->checksum = crcTmp;
}
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
{
uint16_t checksum = msg->checksum;
crc_accumulate(c, &checksum);
msg->checksum = checksum;
}
/*
return the crc_entry value for a msgid
*/
#ifndef MAVLINK_GET_MSG_ENTRY
MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid)
{
static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS;
/*
use a bisection search to find the right entry. A perfect hash may be better
Note that this assumes the table is sorted by msgid
*/
uint32_t low=0, high=sizeof(mavlink_message_crcs)/sizeof(mavlink_message_crcs[0]) - 1;
while (low < high) {
uint32_t mid = (low+1+high)/2;
if (msgid < mavlink_message_crcs[mid].msgid) {
high = mid-1;
continue;
}
if (msgid > mavlink_message_crcs[mid].msgid) {
low = mid;
continue;
}
low = mid;
break;
}
if (mavlink_message_crcs[low].msgid != msgid) {
// msgid is not in the table
return NULL;
}
return &mavlink_message_crcs[low];
}
#endif // MAVLINK_GET_MSG_ENTRY
/*
return the crc_extra value for a message
*/
MAVLINK_HELPER uint8_t mavlink_get_crc_extra(const mavlink_message_t *msg)
{
const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid);
return e?e->crc_extra:0;
}
/*
return the min message length
*/
#define MAVLINK_HAVE_MIN_MESSAGE_LENGTH
MAVLINK_HELPER uint8_t mavlink_min_message_length(const mavlink_message_t *msg)
{
const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid);
return e?e->min_msg_len:0;
}
/*
return the max message length (including extensions)
*/
#define MAVLINK_HAVE_MAX_MESSAGE_LENGTH
MAVLINK_HELPER uint8_t mavlink_max_message_length(const mavlink_message_t *msg)
{
const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid);
return e?e->max_msg_len:0;
}
/**
* This is a variant of mavlink_frame_char() but with caller supplied
* parsing buffers. It is useful when you want to create a MAVLink
* parser in a library that doesn't use any global variables
*
* @param rxmsg parsing message buffer
* @param status parsing status buffer
* @param c The char to parse
*
* @param r_message NULL if no message could be decoded, otherwise the message data
* @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
* @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
*
*/
MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
mavlink_status_t* status,
uint8_t c,
mavlink_message_t* r_message,
mavlink_status_t* r_mavlink_status)
{
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
switch (status->parse_state)
{
case MAVLINK_PARSE_STATE_UNINIT:
case MAVLINK_PARSE_STATE_IDLE:
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
rxmsg->magic = c;
status->flags &= ~MAVLINK_STATUS_FLAG_IN_MAVLINK1;
mavlink_start_checksum(rxmsg);
} else if (c == MAVLINK_STX_MAVLINK1)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
rxmsg->magic = c;
status->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
mavlink_start_checksum(rxmsg);
}
break;
case MAVLINK_PARSE_STATE_GOT_STX:
if (status->msg_received
/* Support shorter buffers than the
default maximum packet size */
#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
|| c > MAVLINK_MAX_PAYLOAD_LEN
#endif
)
{
status->buffer_overrun++;
_mav_parse_error(status);
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
}
else
{
// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
rxmsg->len = c;
status->packet_idx = 0;
mavlink_update_checksum(rxmsg, c);
if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
rxmsg->incompat_flags = 0;
rxmsg->compat_flags = 0;
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS;
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
}
}
break;
case MAVLINK_PARSE_STATE_GOT_LENGTH:
rxmsg->incompat_flags = c;
if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) {
// message includes an incompatible feature flag
_mav_parse_error(status);
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
break;
}
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS;
break;
case MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS:
rxmsg->compat_flags = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS;
break;
case MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS:
rxmsg->seq = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
break;
case MAVLINK_PARSE_STATE_GOT_SEQ:
rxmsg->sysid = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
break;
case MAVLINK_PARSE_STATE_GOT_SYSID:
rxmsg->compid = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
break;
case MAVLINK_PARSE_STATE_GOT_COMPID:
rxmsg->msgid = c;
mavlink_update_checksum(rxmsg, c);
if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
if(rxmsg->len > 0) {
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
if (rxmsg->len < mavlink_min_message_length(rxmsg) ||
rxmsg->len > mavlink_max_message_length(rxmsg)) {
_mav_parse_error(status);
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
break;
}
#endif
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID1;
}
break;
case MAVLINK_PARSE_STATE_GOT_MSGID1:
rxmsg->msgid |= c<<8;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID2;
break;
case MAVLINK_PARSE_STATE_GOT_MSGID2:
rxmsg->msgid |= ((uint32_t)c)<<16;
mavlink_update_checksum(rxmsg, c);
if(rxmsg->len > 0){
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
if (rxmsg->len < mavlink_min_message_length(rxmsg) ||
rxmsg->len > mavlink_max_message_length(rxmsg))
{
_mav_parse_error(status);
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
break;
}
#endif
break;
case MAVLINK_PARSE_STATE_GOT_MSGID3:
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
mavlink_update_checksum(rxmsg, c);
if (status->packet_idx == rxmsg->len)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
break;
case MAVLINK_PARSE_STATE_GOT_PAYLOAD: {
const mavlink_msg_entry_t *e = mavlink_get_msg_entry(rxmsg->msgid);
uint8_t crc_extra = e?e->crc_extra:0;
mavlink_update_checksum(rxmsg, crc_extra);
if (c != (rxmsg->checksum & 0xFF)) {
status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;
} else {
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
}
rxmsg->ck[0] = c;
// zero-fill the packet to cope with short incoming packets
if (e && status->packet_idx < e->max_msg_len) {
memset(&_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx], 0, e->max_msg_len - status->packet_idx);
}
break;
}
case MAVLINK_PARSE_STATE_GOT_CRC1:
case MAVLINK_PARSE_STATE_GOT_BAD_CRC1:
if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) {
// got a bad CRC message
status->msg_received = MAVLINK_FRAMING_BAD_CRC;
} else {
// Successfully got message
status->msg_received = MAVLINK_FRAMING_OK;
}
rxmsg->ck[1] = c;
if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) {
status->parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT;
status->signature_wait = MAVLINK_SIGNATURE_BLOCK_LEN;
// If the CRC is already wrong, don't overwrite msg_received,
// otherwise we can end up with garbage flagged as valid.
if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
}
} else {
if (status->signing &&
(status->signing->accept_unsigned_callback == NULL ||
!status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
// If the CRC is already wrong, don't overwrite msg_received.
if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE;
}
}
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (r_message != NULL) {
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
}
break;
case MAVLINK_PARSE_STATE_SIGNATURE_WAIT:
rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c;
status->signature_wait--;
if (status->signature_wait == 0) {
// we have the whole signature, check it is OK
#ifndef MAVLINK_NO_SIGNATURE_CHECK
bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg);
#else
bool sig_ok = true;
#endif
if (!sig_ok &&
(status->signing->accept_unsigned_callback &&
status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
// accepted via application level override
sig_ok = true;
}
if (sig_ok) {
status->msg_received = MAVLINK_FRAMING_OK;
} else {
status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE;
}
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (r_message !=NULL) {
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
}
break;
}
// If a message has been successfully decoded, check index
if (status->msg_received == MAVLINK_FRAMING_OK)
{
//while(status->current_seq != rxmsg->seq)
//{
// status->packet_rx_drop_count++;
// status->current_seq++;
//}
status->current_rx_seq = rxmsg->seq;
// Initial condition: If no packet has been received so far, drop count is undefined
if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
// Count this packet as received
status->packet_rx_success_count++;
}
if (r_message != NULL) {
r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg
}
if (r_mavlink_status != NULL) {
r_mavlink_status->parse_state = status->parse_state;
r_mavlink_status->packet_idx = status->packet_idx;
r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
r_mavlink_status->packet_rx_drop_count = status->parse_error;
r_mavlink_status->flags = status->flags;
}
status->parse_error = 0;
if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
/*
the CRC came out wrong. We now need to overwrite the
msg CRC with the one on the wire so that if the
caller decides to forward the message anyway that
mavlink_msg_to_send_buffer() won't overwrite the
checksum
*/
if (r_message != NULL) {
r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8);
}
}
return status->msg_received;
}
/**
* This is a convenience function which handles the complete MAVLink parsing.
* the function will parse one byte at a time and return the complete packet once
* it could be successfully decoded. This function will return 0, 1 or
* 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC)
*
* Messages are parsed into an internal buffer (one for each channel). When a complete
* message is received it is copies into *r_message and the channel's status is
* copied into *r_mavlink_status.
*
* @param chan ID of the channel to be parsed.
* A channel is not a physical message channel like a serial port, but a logical partition of
* the communication streams. COMM_NB is the limit for the number of channels
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
* @param c The char to parse
*
* @param r_message NULL if no message could be decoded, otherwise the message data
* @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
* @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
*
* A typical use scenario of this function call is:
*
* @code
* #include <mavlink.h>
*
* mavlink_status_t status;
* mavlink_message_t msg;
* int chan = 0;
*
*
* while(serial.bytesAvailable > 0)
* {
* uint8_t byte = serial.getNextByte();
* if (mavlink_frame_char(chan, byte, &msg, &status) != MAVLINK_FRAMING_INCOMPLETE)
* {
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
* }
* }
*
*
* @endcode
*/
MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan),
mavlink_get_channel_status(chan),
c,
r_message,
r_mavlink_status);
}
/**
* Set the protocol version
*/
MAVLINK_HELPER void mavlink_set_proto_version(uint8_t chan, unsigned int version)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
if (version > 1) {
status->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1);
} else {
status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
}
/**
* Get the protocol version
*
* @return 1 for v1, 2 for v2
*/
MAVLINK_HELPER unsigned int mavlink_get_proto_version(uint8_t chan)
{
mavlink_status_t *status = mavlink_get_channel_status(chan);
if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) {
return 1;
} else {
return 2;
}
}
/**
* This is a convenience function which handles the complete MAVLink parsing.
* the function will parse one byte at a time and return the complete packet once
* it could be successfully decoded. This function will return 0 or 1.
*
* Messages are parsed into an internal buffer (one for each channel). When a complete
* message is received it is copies into *r_message and the channel's status is
* copied into *r_mavlink_status.
*
* @param chan ID of the channel to be parsed.
* A channel is not a physical message channel like a serial port, but a logical partition of
* the communication streams. COMM_NB is the limit for the number of channels
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
* @param c The char to parse
*
* @param r_message NULL if no message could be decoded, otherwise the message data
* @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
* @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC
*
* A typical use scenario of this function call is:
*
* @code
* #include <mavlink.h>
*
* mavlink_status_t status;
* mavlink_message_t msg;
* int chan = 0;
*
*
* while(serial.bytesAvailable > 0)
* {
* uint8_t byte = serial.getNextByte();
* if (mavlink_parse_char(chan, byte, &msg, &status))
* {
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
* }
* }
*
*
* @endcode
*/
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);
if (msg_received == MAVLINK_FRAMING_BAD_CRC ||
msg_received == MAVLINK_FRAMING_BAD_SIGNATURE) {
// we got a bad CRC. Treat as a parse failure
mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
mavlink_status_t* status = mavlink_get_channel_status(chan);
_mav_parse_error(status);
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{