5#include "mavlink_types.h"
13#include "mavlink_sha256.h"
15#ifdef MAVLINK_USE_CXX_NAMESPACE
22#ifndef MAVLINK_GET_CHANNEL_STATUS
25#ifdef MAVLINK_EXTERNAL_RX_STATUS
31 return &m_mavlink_status[chan];
38#ifndef MAVLINK_GET_CHANNEL_BUFFER
39MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
42#ifdef MAVLINK_EXTERNAL_RX_BUFFER
46 static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
48 return &m_mavlink_buffer[chan];
55MAVLINK_HELPER
void mavlink_reset_channel_status(uint8_t chan)
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,
75 if (signing == NULL || !(signing->
flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
78 signature[0] = signing->
link_id;
80 memcpy(&signature[1], tstamp.t8, 6);
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]);
91 return MAVLINK_SIGNATURE_BLOCK_LEN;
99MAVLINK_HELPER uint8_t _mav_trim_payload(
const char *payload, uint8_t length)
101 while (length > 1 && payload[length-1] == 0) {
112 const mavlink_message_t *msg)
114 if (signing == NULL) {
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];
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) {
135 bool timestamp_checks = !(signing->
flags & MAVLINK_SIGNING_FLAG_NO_TIMESTAMPS);
140 uint8_t link_id = psig[0];
142 memcpy(tstamp.t8, psig+1, 6);
144 if (signing_streams == NULL) {
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) {
156 if (i == signing_streams->num_signing_streams) {
157 if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) {
162 if (timestamp_checks && (tstamp.t64 + 6000*1000UL < signing->
timestamp)) {
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++;
171 union tstamp last_tstamp;
173 memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6);
174 if (timestamp_checks && tstamp.t64 <= last_tstamp.t64) {
181 memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6);
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)
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];
212 msg->magic = MAVLINK_STX_MAVLINK1;
213 header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1;
215 msg->magic = MAVLINK_STX;
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;
222 msg->incompat_flags |= MAVLINK_IFLAG_SIGNED;
224 msg->compat_flags = 0;
234 buf[4] = msg->compid;
235 buf[5] = msg->msgid & 0xFF;
237 buf[2] = msg->incompat_flags;
238 buf[3] = msg->compat_flags;
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;
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);
254 mavlink_sign_packet(status->
signing,
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);
261 return msg->len + header_len + 2 + signature_len;
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)
268 return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra);
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)
277 return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);
285#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
286MAVLINK_HELPER
void _mavlink_send_uart(mavlink_channel_t chan,
const char *buf, uint16_t len);
291MAVLINK_HELPER
void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid,
293 uint8_t min_length, uint8_t length, uint8_t crc_extra)
296 uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
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);
309 _mav_parse_error(status);
312 header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN;
313 buf[0] = MAVLINK_STX_MAVLINK1;
316 buf[3] = mavlink_system.sysid;
317 buf[4] = mavlink_system.compid;
318 buf[5] = msgid & 0xFF;
320 uint8_t incompat_flags = 0;
322 incompat_flags |= MAVLINK_IFLAG_SIGNED;
324 length = _mav_trim_payload(packet, length);
325 buf[0] = MAVLINK_STX;
327 buf[2] = incompat_flags;
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;
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);
345 signature_len = mavlink_sign_packet(status->
signing, signature, buf, header_len+1,
346 (
const uint8_t *)packet, length, ck);
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);
356 MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
364MAVLINK_HELPER
void _mavlink_resend_uart(mavlink_channel_t chan,
const mavlink_message_t *msg)
368 ck[0] = (uint8_t)(msg->checksum & 0xFF);
369 ck[1] = (uint8_t)(msg->checksum >> 8);
373 uint8_t signature_len;
375 if (msg->magic == MAVLINK_STX_MAVLINK1) {
376 header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1;
378 MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
380 uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1];
385 buf[4] = msg->compid;
386 buf[5] = msg->msgid & 0xFF;
387 _mavlink_send_uart(chan, (
const char*)buf, header_len);
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];
395 buf[2] = msg->incompat_flags;
396 buf[3] = msg->compat_flags;
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);
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);
410 MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
417MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buf,
const mavlink_message_t *msg)
419 uint8_t signature_len, header_len;
421 uint8_t length = msg->len;
423 if (msg->magic == MAVLINK_STX_MAVLINK1) {
425 header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN;
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;
435 length = _mav_trim_payload(_MAV_PAYLOAD(msg), length);
436 header_len = MAVLINK_CORE_HEADER_LEN;
439 buf[2] = msg->incompat_flags;
440 buf[3] = msg->compat_flags;
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;
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);
457 return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len;
470MAVLINK_HELPER
void mavlink_start_checksum(mavlink_message_t* msg)
472 crc_init(&msg->checksum);
475MAVLINK_HELPER
void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
477 crc_accumulate(c, &msg->checksum);
483#ifndef MAVLINK_GET_MSG_ENTRY
491 uint32_t low=0, high=
sizeof(mavlink_message_crcs)/
sizeof(mavlink_message_crcs[0]);
493 uint32_t mid = (low+1+high)/2;
494 if (msgid < mavlink_message_crcs[mid].msgid) {
498 if (msgid > mavlink_message_crcs[mid].msgid) {
505 if (mavlink_message_crcs[low].msgid != msgid) {
509 return &mavlink_message_crcs[low];
516MAVLINK_HELPER uint8_t mavlink_get_crc_extra(
const mavlink_message_t *msg)
519 return e?e->crc_extra:0;
525#define MAVLINK_HAVE_EXPECTED_MESSAGE_LENGTH
526MAVLINK_HELPER uint8_t mavlink_expected_message_length(
const mavlink_message_t *msg)
529 return e?e->msg_len:0;
566MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
569 mavlink_message_t* r_message,
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]
591 case MAVLINK_PARSE_STATE_UNINIT:
592 case MAVLINK_PARSE_STATE_IDLE:
593 if (c == MAVLINK_STX)
598 status->
flags &= ~MAVLINK_STATUS_FLAG_IN_MAVLINK1;
599 mavlink_start_checksum(rxmsg);
600 }
else if (c == MAVLINK_STX_MAVLINK1)
605 status->
flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
606 mavlink_start_checksum(rxmsg);
610 case MAVLINK_PARSE_STATE_GOT_STX:
614#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
615 || c > MAVLINK_MAX_PAYLOAD_LEN
620 _mav_parse_error(status);
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;
635 status->
parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
640 case MAVLINK_PARSE_STATE_GOT_LENGTH:
641 rxmsg->incompat_flags = c;
642 if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) {
644 _mav_parse_error(status);
649 mavlink_update_checksum(rxmsg, c);
650 status->
parse_state = MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS;
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;
659 case MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS:
661 mavlink_update_checksum(rxmsg, c);
665 case MAVLINK_PARSE_STATE_GOT_SEQ:
667 mavlink_update_checksum(rxmsg, c);
668 status->
parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
671 case MAVLINK_PARSE_STATE_GOT_SYSID:
673 mavlink_update_checksum(rxmsg, c);
674 status->
parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
677 case MAVLINK_PARSE_STATE_GOT_COMPID:
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))
685 _mav_parse_error(status);
691 status->
parse_state = MAVLINK_PARSE_STATE_GOT_MSGID1;
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;
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))
708 _mav_parse_error(status);
715 case MAVLINK_PARSE_STATE_GOT_MSGID3:
716 _MAV_PAYLOAD_NON_CONST(rxmsg)[status->
packet_idx++] = (char)c;
717 mavlink_update_checksum(rxmsg, c);
720 status->
parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
724 case MAVLINK_PARSE_STATE_GOT_PAYLOAD: {
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;
731 status->
parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
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)) {
753 if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) {
754 status->
parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT;
764 (status->
signing->accept_unsigned_callback == NULL ||
765 !status->
signing->accept_unsigned_callback(status, rxmsg->msgid))) {
773 memcpy(r_message, rxmsg,
sizeof(mavlink_message_t));
776 case MAVLINK_PARSE_STATE_SIGNATURE_WAIT:
777 rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->
signature_wait] = c;
781 MAVLINK_START_SIGN_STREAM(status->
signing->link_id);
783 MAVLINK_END_SIGN_STREAM(status->
signing->link_id);
785 (status->
signing->accept_unsigned_callback &&
786 status->
signing->accept_unsigned_callback(status, rxmsg->msgid))) {
796 memcpy(r_message, rxmsg,
sizeof(mavlink_message_t));
817 r_message->len = rxmsg->len;
834 r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8);
881MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message,
mavlink_status_t* r_mavlink_status)
883 return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan),
884 mavlink_get_channel_status(chan),
893MAVLINK_HELPER
void mavlink_set_proto_version(uint8_t chan,
unsigned int version)
897 status->
flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1);
899 status->
flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
908MAVLINK_HELPER
unsigned int mavlink_get_proto_version(uint8_t chan)
911 if ((status->
flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) {
958MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message,
mavlink_status_t* r_mavlink_status)
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) {
964 mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
966 _mav_parse_error(status);
969 if (c == MAVLINK_STX)
973 mavlink_start_checksum(rxmsg);
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)
992 uint16_t bits_remain = bits;
995 uint8_t i_bit_index, i_byte_index, curr_bits_n;
996#if MAVLINK_NEED_BYTE_SWAP
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];
1027 i_bit_index = bit_index;
1028 i_byte_index = packet_index;
1037 while (bits_remain > 0)
1046 if (bits_remain <= (uint8_t)(8 - i_bit_index))
1049 curr_bits_n = (uint8_t)bits_remain;
1053 curr_bits_n = (8 - i_bit_index);
1058 buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
1060 buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
1063 i_bit_index += curr_bits_n;
1066 bits_remain -= curr_bits_n;
1067 if (bits_remain > 0)
1075 *r_bit_index = i_bit_index;
1077 if (i_bit_index != 7) i_byte_index++;
1078 return i_byte_index - packet_index;
1081#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
1104MAVLINK_HELPER
void _mavlink_send_uart(mavlink_channel_t chan,
const char *buf, uint16_t len)
1106#ifdef MAVLINK_SEND_UART_BYTES
1109 MAVLINK_SEND_UART_BYTES(chan, (
const uint8_t *)buf, len);
1113 for (i = 0; i < len; i++) {
1114 comm_send_ch(chan, (uint8_t)buf[i]);
1120#ifdef MAVLINK_USE_CXX_NAMESPACE
uint64_t timestamp
Timestamp, in microseconds since UNIX epoch GMT
定义 mavlink_types.h:252
uint8_t flags
MAVLINK_SIGNING_FLAG_*
定义 mavlink_types.h:250
uint8_t link_id
Same as MAVLINK_CHANNEL
定义 mavlink_types.h:251
uint8_t parse_error
Number of parse errors
定义 mavlink_types.h:220
struct __mavlink_signing_streams * signing_streams
global record of stream timestamps
定义 mavlink_types.h:230
uint16_t packet_rx_success_count
Received packets
定义 mavlink_types.h:225
uint8_t buffer_overrun
Number of buffer overruns
定义 mavlink_types.h:219
mavlink_parse_state_t parse_state
Parsing state machine
定义 mavlink_types.h:221
uint8_t flags
MAVLINK_STATUS_FLAG_*
定义 mavlink_types.h:227
uint16_t packet_rx_drop_count
Number of packet drops
定义 mavlink_types.h:226
uint8_t msg_received
Number of received messages
定义 mavlink_types.h:218
uint8_t current_tx_seq
Sequence number of last packet sent
定义 mavlink_types.h:224
uint8_t signature_wait
number of signature bytes left to receive
定义 mavlink_types.h:228
uint8_t packet_idx
Index in current packet
定义 mavlink_types.h:222
uint8_t current_rx_seq
Sequence number of last packet received
定义 mavlink_types.h:223
struct __mavlink_signing * signing
optional signing state
定义 mavlink_types.h:229