1 #ifndef _MAVLINK_HELPERS_H_
2 #define _MAVLINK_HELPERS_H_
6 #include "mavlink_types.h"
7 #include "mavlink_conversions.h"
10 #define MAVLINK_HELPER
14 * Internal function to give access to the channel status for each channel
16 #ifndef MAVLINK_GET_CHANNEL_STATUS
17 MAVLINK_HELPER mavlink_status_t
* mavlink_get_channel_status(uint8_t chan
)
19 #ifdef MAVLINK_EXTERNAL_RX_STATUS
20 // No m_mavlink_status array defined in function,
21 // has to be defined externally
23 static mavlink_status_t m_mavlink_status
[MAVLINK_COMM_NUM_BUFFERS
];
25 return &m_mavlink_status
[chan
];
30 * Internal function to give access to the channel buffer for each channel
32 #ifndef MAVLINK_GET_CHANNEL_BUFFER
33 MAVLINK_HELPER mavlink_message_t
* mavlink_get_channel_buffer(uint8_t chan
)
36 #ifdef MAVLINK_EXTERNAL_RX_BUFFER
37 // No m_mavlink_buffer array defined in function,
38 // has to be defined externally
40 static mavlink_message_t m_mavlink_buffer
[MAVLINK_COMM_NUM_BUFFERS
];
42 return &m_mavlink_buffer
[chan
];
47 * @brief Reset the status of a channel.
49 MAVLINK_HELPER
void mavlink_reset_channel_status(uint8_t chan
)
51 mavlink_status_t
*status
= mavlink_get_channel_status(chan
);
52 status
->parse_state
= MAVLINK_PARSE_STATE_IDLE
;
56 * @brief Finalize a MAVLink message with channel assignment
58 * This function calculates the checksum and sets length and aircraft id correctly.
59 * It assumes that the message id and the payload are already correctly set. This function
60 * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
61 * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
63 * @param msg Message to finalize
64 * @param system_id Id of the sending (this) system, 1-127
65 * @param length Message length
68 MAVLINK_HELPER
uint16_t mavlink_finalize_message_chan(mavlink_message_t
* msg
, uint8_t system_id
, uint8_t component_id
,
69 uint8_t chan
, uint8_t length
, uint8_t crc_extra
)
71 MAVLINK_HELPER
uint16_t mavlink_finalize_message_chan(mavlink_message_t
* msg
, uint8_t system_id
, uint8_t component_id
,
72 uint8_t chan
, uint8_t length
)
75 // This code part is the same for all messages;
76 msg
->magic
= MAVLINK_STX
;
78 msg
->sysid
= system_id
;
79 msg
->compid
= component_id
;
80 // One sequence number per channel
81 msg
->seq
= mavlink_get_channel_status(chan
)->current_tx_seq
;
82 mavlink_get_channel_status(chan
)->current_tx_seq
= mavlink_get_channel_status(chan
)->current_tx_seq
+1;
83 msg
->checksum
= crc_calculate(((const uint8_t*)(msg
)) + 3, MAVLINK_CORE_HEADER_LEN
);
84 crc_accumulate_buffer(&msg
->checksum
, _MAV_PAYLOAD(msg
), msg
->len
);
86 crc_accumulate(crc_extra
, &msg
->checksum
);
88 mavlink_ck_a(msg
) = (uint8_t)(msg
->checksum
& 0xFF);
89 mavlink_ck_b(msg
) = (uint8_t)(msg
->checksum
>> 8);
91 return length
+ MAVLINK_NUM_NON_PAYLOAD_BYTES
;
96 * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
99 MAVLINK_HELPER
uint16_t mavlink_finalize_message(mavlink_message_t
* msg
, uint8_t system_id
, uint8_t component_id
,
100 uint8_t length
, uint8_t crc_extra
)
102 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, MAVLINK_COMM_0
, length
, crc_extra
);
105 MAVLINK_HELPER
uint16_t mavlink_finalize_message(mavlink_message_t
* msg
, uint8_t system_id
, uint8_t component_id
,
108 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, MAVLINK_COMM_0
, length
);
112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
113 MAVLINK_HELPER
void _mavlink_send_uart(mavlink_channel_t chan
, const char *buf
, uint16_t len
);
116 * @brief Finalize a MAVLink message with channel assignment and send
118 #if MAVLINK_CRC_EXTRA
119 MAVLINK_HELPER
void _mav_finalize_message_chan_send(mavlink_channel_t chan
, uint8_t msgid
, const char *packet
,
120 uint8_t length
, uint8_t crc_extra
)
122 MAVLINK_HELPER
void _mav_finalize_message_chan_send(mavlink_channel_t chan
, uint8_t msgid
, const char *packet
, uint8_t length
)
126 uint8_t buf
[MAVLINK_NUM_HEADER_BYTES
];
128 mavlink_status_t
*status
= mavlink_get_channel_status(chan
);
129 buf
[0] = MAVLINK_STX
;
131 buf
[2] = status
->current_tx_seq
;
132 buf
[3] = mavlink_system
.sysid
;
133 buf
[4] = mavlink_system
.compid
;
135 status
->current_tx_seq
++;
136 checksum
= crc_calculate((const uint8_t*)&buf
[1], MAVLINK_CORE_HEADER_LEN
);
137 crc_accumulate_buffer(&checksum
, packet
, length
);
138 #if MAVLINK_CRC_EXTRA
139 crc_accumulate(crc_extra
, &checksum
);
141 ck
[0] = (uint8_t)(checksum
& 0xFF);
142 ck
[1] = (uint8_t)(checksum
>> 8);
144 MAVLINK_START_UART_SEND(chan
, MAVLINK_NUM_NON_PAYLOAD_BYTES
+ (uint16_t)length
);
145 _mavlink_send_uart(chan
, (const char *)buf
, MAVLINK_NUM_HEADER_BYTES
);
146 _mavlink_send_uart(chan
, packet
, length
);
147 _mavlink_send_uart(chan
, (const char *)ck
, 2);
148 MAVLINK_END_UART_SEND(chan
, MAVLINK_NUM_NON_PAYLOAD_BYTES
+ (uint16_t)length
);
152 * @brief re-send a message over a uart channel
153 * this is more stack efficient than re-marshalling the message
155 MAVLINK_HELPER
void _mavlink_resend_uart(mavlink_channel_t chan
, const mavlink_message_t
*msg
)
159 ck
[0] = (uint8_t)(msg
->checksum
& 0xFF);
160 ck
[1] = (uint8_t)(msg
->checksum
>> 8);
161 // XXX use the right sequence here
163 MAVLINK_START_UART_SEND(chan
, MAVLINK_NUM_NON_PAYLOAD_BYTES
+ msg
->len
);
164 _mavlink_send_uart(chan
, (const char *)&msg
->magic
, MAVLINK_NUM_HEADER_BYTES
);
165 _mavlink_send_uart(chan
, _MAV_PAYLOAD(msg
), msg
->len
);
166 _mavlink_send_uart(chan
, (const char *)ck
, 2);
167 MAVLINK_END_UART_SEND(chan
, MAVLINK_NUM_NON_PAYLOAD_BYTES
+ msg
->len
);
169 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
172 * @brief Pack a message to send it over a serial byte stream
174 MAVLINK_HELPER
uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer
, const mavlink_message_t
*msg
)
176 memcpy(buffer
, (const uint8_t *)&msg
->magic
, MAVLINK_NUM_HEADER_BYTES
+ (uint16_t)msg
->len
);
178 uint8_t *ck
= buffer
+ (MAVLINK_NUM_HEADER_BYTES
+ (uint16_t)msg
->len
);
180 ck
[0] = (uint8_t)(msg
->checksum
& 0xFF);
181 ck
[1] = (uint8_t)(msg
->checksum
>> 8);
183 return MAVLINK_NUM_NON_PAYLOAD_BYTES
+ (uint16_t)msg
->len
;
186 union __mavlink_bitfield
{
196 MAVLINK_HELPER
void mavlink_start_checksum(mavlink_message_t
* msg
)
198 crc_init(&msg
->checksum
);
201 MAVLINK_HELPER
void mavlink_update_checksum(mavlink_message_t
* msg
, uint8_t c
)
203 crc_accumulate(c
, &msg
->checksum
);
207 * This is a convenience function which handles the complete MAVLink parsing.
208 * the function will parse one byte at a time and return the complete packet once
209 * it could be successfully decoded. Checksum and other failures will be silently
212 * Messages are parsed into an internal buffer (one for each channel). When a complete
213 * message is received it is copies into *returnMsg and the channel's status is
214 * copied into *returnStats.
216 * @param chan ID of the current channel. This allows to parse different channels with this function.
217 * a channel is not a physical message channel like a serial port, but a logic partition of
218 * the communication streams in this case. COMM_NB is the limit for the number of channels
219 * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
220 * @param c The char to parse
222 * @param returnMsg NULL if no message could be decoded, the message data else
223 * @param returnStats if a message was decoded, this is filled with the channel's stats
224 * @return 0 if no message could be decoded, 1 else
226 * A typical use scenario of this function call is:
229 * #include <mavlink.h>
231 * mavlink_message_t msg;
235 * while(serial.bytesAvailable > 0)
237 * uint8_t byte = serial.getNextByte();
238 * if (mavlink_parse_char(chan, byte, &msg))
240 * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
247 MAVLINK_HELPER
uint8_t mavlink_parse_char(uint8_t chan
, uint8_t c
, mavlink_message_t
* r_message
, mavlink_status_t
* r_mavlink_status
)
250 default message crc function. You can override this per-system to
251 put this data in a different memory segment
253 #if MAVLINK_CRC_EXTRA
254 #ifndef MAVLINK_MESSAGE_CRC
255 static const uint8_t mavlink_message_crcs
[256] = MAVLINK_MESSAGE_CRCS
;
256 #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
260 /* Enable this option to check the length of each message.
261 This allows invalid messages to be caught much sooner. Use if the transmission
262 medium is prone to missing (or extra) characters (e.g. a radio that fades in
263 and out). Only use if the channel will only contain messages types listed in
266 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
267 #ifndef MAVLINK_MESSAGE_LENGTH
268 static const uint8_t mavlink_message_lengths
[256] = MAVLINK_MESSAGE_LENGTHS
;
269 #define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
273 mavlink_message_t
* rxmsg
= mavlink_get_channel_buffer(chan
); ///< The currently decoded message
274 mavlink_status_t
* status
= mavlink_get_channel_status(chan
); ///< The current decode status
277 status
->msg_received
= 0;
279 switch (status
->parse_state
)
281 case MAVLINK_PARSE_STATE_UNINIT
:
282 case MAVLINK_PARSE_STATE_IDLE
:
283 if (c
== MAVLINK_STX
)
285 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_STX
;
288 mavlink_start_checksum(rxmsg
);
292 case MAVLINK_PARSE_STATE_GOT_STX
:
293 if (status
->msg_received
294 /* Support shorter buffers than the
295 default maximum packet size */
296 #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
297 || c
> MAVLINK_MAX_PAYLOAD_LEN
301 status
->buffer_overrun
++;
302 status
->parse_error
++;
303 status
->msg_received
= 0;
304 status
->parse_state
= MAVLINK_PARSE_STATE_IDLE
;
308 // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
310 status
->packet_idx
= 0;
311 mavlink_update_checksum(rxmsg
, c
);
312 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_LENGTH
;
316 case MAVLINK_PARSE_STATE_GOT_LENGTH
:
318 mavlink_update_checksum(rxmsg
, c
);
319 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_SEQ
;
322 case MAVLINK_PARSE_STATE_GOT_SEQ
:
324 mavlink_update_checksum(rxmsg
, c
);
325 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_SYSID
;
328 case MAVLINK_PARSE_STATE_GOT_SYSID
:
330 mavlink_update_checksum(rxmsg
, c
);
331 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_COMPID
;
334 case MAVLINK_PARSE_STATE_GOT_COMPID
:
335 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
336 if (rxmsg
->len
!= MAVLINK_MESSAGE_LENGTH(c
))
338 status
->parse_error
++;
339 status
->parse_state
= MAVLINK_PARSE_STATE_IDLE
;
344 mavlink_update_checksum(rxmsg
, c
);
347 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_PAYLOAD
;
351 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_MSGID
;
355 case MAVLINK_PARSE_STATE_GOT_MSGID
:
356 _MAV_PAYLOAD_NON_CONST(rxmsg
)[status
->packet_idx
++] = (char)c
;
357 mavlink_update_checksum(rxmsg
, c
);
358 if (status
->packet_idx
== rxmsg
->len
)
360 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_PAYLOAD
;
364 case MAVLINK_PARSE_STATE_GOT_PAYLOAD
:
365 #if MAVLINK_CRC_EXTRA
366 mavlink_update_checksum(rxmsg
, MAVLINK_MESSAGE_CRC(rxmsg
->msgid
));
368 if (c
!= (rxmsg
->checksum
& 0xFF)) {
369 // Check first checksum byte
370 status
->parse_error
++;
371 status
->msg_received
= 0;
372 status
->parse_state
= MAVLINK_PARSE_STATE_IDLE
;
373 if (c
== MAVLINK_STX
)
375 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_STX
;
377 mavlink_start_checksum(rxmsg
);
382 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_CRC1
;
383 _MAV_PAYLOAD_NON_CONST(rxmsg
)[status
->packet_idx
] = (char)c
;
387 case MAVLINK_PARSE_STATE_GOT_CRC1
:
388 if (c
!= (rxmsg
->checksum
>> 8)) {
389 // Check second checksum byte
390 status
->parse_error
++;
391 status
->msg_received
= 0;
392 status
->parse_state
= MAVLINK_PARSE_STATE_IDLE
;
393 if (c
== MAVLINK_STX
)
395 status
->parse_state
= MAVLINK_PARSE_STATE_GOT_STX
;
397 mavlink_start_checksum(rxmsg
);
402 // Successfully got message
403 status
->msg_received
= 1;
404 status
->parse_state
= MAVLINK_PARSE_STATE_IDLE
;
405 _MAV_PAYLOAD_NON_CONST(rxmsg
)[status
->packet_idx
+1] = (char)c
;
406 memcpy(r_message
, rxmsg
, sizeof(mavlink_message_t
));
412 // If a message has been sucessfully decoded, check index
413 if (status
->msg_received
== 1)
415 //while(status->current_seq != rxmsg->seq)
417 // status->packet_rx_drop_count++;
418 // status->current_seq++;
420 status
->current_rx_seq
= rxmsg
->seq
;
421 // Initial condition: If no packet has been received so far, drop count is undefined
422 if (status
->packet_rx_success_count
== 0) status
->packet_rx_drop_count
= 0;
423 // Count this packet as received
424 status
->packet_rx_success_count
++;
427 r_message
->len
= rxmsg
->len
; // Provide visibility on how far we are into current msg
428 r_mavlink_status
->parse_state
= status
->parse_state
;
429 r_mavlink_status
->packet_idx
= status
->packet_idx
;
430 r_mavlink_status
->current_rx_seq
= status
->current_rx_seq
+1;
431 r_mavlink_status
->packet_rx_success_count
= status
->packet_rx_success_count
;
432 r_mavlink_status
->packet_rx_drop_count
= status
->parse_error
;
433 status
->parse_error
= 0;
434 return status
->msg_received
;
438 * @brief Put a bitfield of length 1-32 bit into the buffer
440 * @param b the value to add, will be encoded in the bitfield
441 * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
442 * @param packet_index the position in the packet (the index of the first byte to use)
443 * @param bit_index the position in the byte (the index of the first bit to use)
444 * @param buffer packet buffer to write into
445 * @return new position of the last used byte in the buffer
447 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
)
449 uint16_t bits_remain
= bits
;
450 // Transform number into network order
452 uint8_t i_bit_index
, i_byte_index
, curr_bits_n
;
453 #if MAVLINK_NEED_BYTE_SWAP
459 bout
.b
[0] = bin
.b
[3];
460 bout
.b
[1] = bin
.b
[2];
461 bout
.b
[2] = bin
.b
[1];
462 bout
.b
[3] = bin
.b
[0];
469 // 01100000 01000000 00000000 11110001
471 // 11110001 00000000 01000000 01100000
473 // Existing partly filled byte (four free slots)
477 // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
478 // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
480 // Shift n bits into the right position
483 // Mask and shift bytes
484 i_bit_index
= bit_index
;
485 i_byte_index
= packet_index
;
488 // If bits were available at start, they were available
489 // in the byte before the current index
493 // While bits have not been packed yet
494 while (bits_remain
> 0)
496 // Bits still have to be packed
497 // there can be more than 8 bits, so
498 // we might have to pack them into more than one byte
500 // First pack everything we can into the current 'open' byte
501 //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
503 if (bits_remain
<= (uint8_t)(8 - i_bit_index
))
506 curr_bits_n
= (uint8_t)bits_remain
;
510 curr_bits_n
= (8 - i_bit_index
);
513 // Pack these n bits into the current byte
514 // Mask out whatever was at that position with ones (xxx11111)
515 buffer
[i_byte_index
] &= (0xFF >> (8 - curr_bits_n
));
516 // Put content to this position, by masking out the non-used part
517 buffer
[i_byte_index
] |= ((0x00 << curr_bits_n
) & v
);
519 // Increment the bit index
520 i_bit_index
+= curr_bits_n
;
522 // Now proceed to the next byte, if necessary
523 bits_remain
-= curr_bits_n
;
526 // Offer another 8 bits / one byte
532 *r_bit_index
= i_bit_index
;
533 // If a partly filled byte is present, mark this as consumed
534 if (i_bit_index
!= 7) i_byte_index
++;
535 return i_byte_index
- packet_index
;
538 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
540 // To make MAVLink work on your MCU, define comm_send_ch() if you wish
541 // to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
542 // whole packet at a time
546 #include "mavlink_types.h"
548 void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
550 if (chan == MAVLINK_COMM_0)
554 if (chan == MAVLINK_COMM_1)
561 MAVLINK_HELPER
void _mavlink_send_uart(mavlink_channel_t chan
, const char *buf
, uint16_t len
)
563 #ifdef MAVLINK_SEND_UART_BYTES
564 /* this is the more efficient approach, if the platform
566 MAVLINK_SEND_UART_BYTES(chan
, (const uint8_t *)buf
, len
);
568 /* fallback to one byte at a time */
570 for (i
= 0; i
< len
; i
++) {
571 comm_send_ch(chan
, (uint8_t)buf
[i
]);
575 #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
577 #endif /* _MAVLINK_HELPERS_H_ */