@@ -52,6 +52,46 @@ MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
5252 status -> parse_state = MAVLINK_PARSE_STATE_IDLE ;
5353}
5454
55+ /**
56+ * @brief Finalize a MAVLink message with channel assignment
57+ *
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.
62+ *
63+ * @param msg Message to finalize
64+ * @param system_id Id of the sending (this) system, 1-127
65+ * @param length Message length
66+ */
67+ #if MAVLINK_CRC_EXTRA
68+ MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer (mavlink_message_t * msg , uint8_t system_id , uint8_t component_id ,
69+ mavlink_status_t * status , uint8_t min_length , uint8_t length , uint8_t crc_extra )
70+ #else
71+ MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer (mavlink_message_t * msg , uint8_t system_id , uint8_t component_id ,
72+ mavlink_status_t * status , uint8_t length )
73+ #endif
74+ {
75+ // This is only used for the v2 protocol and we silence it here
76+ (void )min_length ;
77+ // This code part is the same for all messages;
78+ msg -> magic = MAVLINK_STX ;
79+ msg -> len = length ;
80+ msg -> sysid = system_id ;
81+ msg -> compid = component_id ;
82+ msg -> seq = status -> current_tx_seq ;
83+ status -> current_tx_seq = status -> current_tx_seq + 1 ;
84+ msg -> checksum = crc_calculate (((const uint8_t * )(msg )) + 3 , MAVLINK_CORE_HEADER_LEN );
85+ crc_accumulate_buffer (& msg -> checksum , _MAV_PAYLOAD (msg ), msg -> len );
86+ #if MAVLINK_CRC_EXTRA
87+ crc_accumulate (crc_extra , & msg -> checksum );
88+ #endif
89+ mavlink_ck_a (msg ) = (uint8_t )(msg -> checksum & 0xFF );
90+ mavlink_ck_b (msg ) = (uint8_t )(msg -> checksum >> 8 );
91+
92+ return length + MAVLINK_NUM_NON_PAYLOAD_BYTES ;
93+ }
94+
5595/**
5696 * @brief Finalize a MAVLink message with channel assignment
5797 *
@@ -66,12 +106,14 @@ MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
66106 */
67107#if MAVLINK_CRC_EXTRA
68108MAVLINK_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 )
109+ uint8_t chan , uint8_t min_length , uint8_t length , uint8_t crc_extra )
70110#else
71111MAVLINK_HELPER uint16_t mavlink_finalize_message_chan (mavlink_message_t * msg , uint8_t system_id , uint8_t component_id ,
72112 uint8_t chan , uint8_t length )
73113#endif
74114{
115+ // This is only used for the v2 protocol and we silence it here
116+ (void )min_length ;
75117 // This code part is the same for all messages;
76118 msg -> magic = MAVLINK_STX ;
77119 msg -> len = length ;
@@ -97,9 +139,9 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
97139 */
98140#if MAVLINK_CRC_EXTRA
99141MAVLINK_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 )
142+ uint8_t min_length , uint8_t length , uint8_t crc_extra )
101143{
102- return mavlink_finalize_message_chan (msg , system_id , component_id , MAVLINK_COMM_0 , length , crc_extra );
144+ return mavlink_finalize_message_chan (msg , system_id , component_id , MAVLINK_COMM_0 , min_length , length , crc_extra );
103145}
104146#else
105147MAVLINK_HELPER uint16_t mavlink_finalize_message (mavlink_message_t * msg , uint8_t system_id , uint8_t component_id ,
@@ -117,7 +159,7 @@ MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf,
117159 */
118160#if MAVLINK_CRC_EXTRA
119161MAVLINK_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 )
162+ uint8_t min_length , uint8_t length , uint8_t crc_extra )
121163#else
122164MAVLINK_HELPER void _mav_finalize_message_chan_send (mavlink_channel_t chan , uint8_t msgid , const char * packet , uint8_t length )
123165#endif
@@ -204,38 +246,17 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
204246}
205247
206248/**
207- * This is a varient of mavlink_frame_char() but with caller supplied
249+ * This is a variant of mavlink_frame_char() but with caller supplied
208250 * parsing buffers. It is useful when you want to create a MAVLink
209251 * parser in a library that doesn't use any global variables
210252 *
211253 * @param rxmsg parsing message buffer
212- * @param status parsing starus buffer
254+ * @param status parsing status buffer
213255 * @param c The char to parse
214256 *
215- * @param returnMsg NULL if no message could be decoded, the message data else
216- * @param returnStats if a message was decoded, this is filled with the channel's stats
257+ * @param r_message NULL if no message could be decoded, otherwise the message data
258+ * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
217259 * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
218- *
219- * A typical use scenario of this function call is:
220- *
221- * @code
222- * #include <mavlink.h>
223- *
224- * mavlink_message_t msg;
225- * int chan = 0;
226- *
227- *
228- * while(serial.bytesAvailable > 0)
229- * {
230- * uint8_t byte = serial.getNextByte();
231- * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)
232- * {
233- * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
234- * }
235- * }
236- *
237- *
238- * @endcode
239260 */
240261MAVLINK_HELPER uint8_t mavlink_frame_char_buffer (mavlink_message_t * rxmsg ,
241262 mavlink_status_t * status ,
@@ -267,8 +288,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
267288#endif
268289#endif
269290
270- int bufferIndex = 0 ;
271-
272291 status -> msg_received = MAVLINK_FRAMING_INCOMPLETE ;
273292
274293 switch (status -> parse_state )
@@ -383,8 +402,7 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
383402 break ;
384403 }
385404
386- bufferIndex ++ ;
387- // If a message has been sucessfully decoded, check index
405+ // If a message has been successfully decoded, check index
388406 if (status -> msg_received == MAVLINK_FRAMING_OK )
389407 {
390408 //while(status->current_seq != rxmsg->seq)
@@ -428,32 +446,33 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
428446 * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC)
429447 *
430448 * Messages are parsed into an internal buffer (one for each channel). When a complete
431- * message is received it is copies into *returnMsg and the channel's status is
432- * copied into *returnStats .
449+ * message is received it is copies into *r_message and the channel's status is
450+ * copied into *r_mavlink_status .
433451 *
434- * @param chan ID of the current channel. This allows to parse different channels with this function .
435- * a channel is not a physical message channel like a serial port, but a logic partition of
436- * the communication streams in this case . COMM_NB is the limit for the number of channels
452+ * @param chan ID of the channel to be parsed .
453+ * A channel is not a physical message channel like a serial port, but a logical partition of
454+ * the communication streams. COMM_NB is the limit for the number of channels
437455 * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
438456 * @param c The char to parse
439457 *
440- * @param returnMsg NULL if no message could be decoded, the message data else
441- * @param returnStats if a message was decoded, this is filled with the channel's stats
458+ * @param r_message NULL if no message could be decoded, the message data else
459+ * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
442460 * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
443461 *
444462 * A typical use scenario of this function call is:
445463 *
446464 * @code
447465 * #include <mavlink.h>
448466 *
467+ * mavlink_status_t status;
449468 * mavlink_message_t msg;
450469 * int chan = 0;
451470 *
452471 *
453472 * while(serial.bytesAvailable > 0)
454473 * {
455474 * uint8_t byte = serial.getNextByte();
456- * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)
475+ * if (mavlink_frame_char(chan, byte, &msg, &status ) != MAVLINK_FRAMING_INCOMPLETE)
457476 * {
458477 * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
459478 * }
@@ -478,32 +497,33 @@ MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_messa
478497 * it could be successfully decoded. This function will return 0 or 1.
479498 *
480499 * Messages are parsed into an internal buffer (one for each channel). When a complete
481- * message is received it is copies into *returnMsg and the channel's status is
482- * copied into *returnStats .
500+ * message is received it is copies into *r_message and the channel's status is
501+ * copied into *r_mavlink_status .
483502 *
484- * @param chan ID of the current channel. This allows to parse different channels with this function .
485- * a channel is not a physical message channel like a serial port, but a logic partition of
486- * the communication streams in this case . COMM_NB is the limit for the number of channels
503+ * @param chan ID of the channel to be parsed .
504+ * A channel is not a physical message channel like a serial port, but a logical partition of
505+ * the communication streams. COMM_NB is the limit for the number of channels
487506 * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
488507 * @param c The char to parse
489508 *
490- * @param returnMsg NULL if no message could be decoded, the message data else
491- * @param returnStats if a message was decoded, this is filled with the channel's stats
509+ * @param r_message NULL if no message could be decoded, otherwise the message data.
510+ * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
492511 * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC
493512 *
494513 * A typical use scenario of this function call is:
495514 *
496515 * @code
497516 * #include <mavlink.h>
498517 *
518+ * mavlink_status_t status;
499519 * mavlink_message_t msg;
500520 * int chan = 0;
501521 *
502522 *
503523 * while(serial.bytesAvailable > 0)
504524 * {
505525 * uint8_t byte = serial.getNextByte();
506- * if (mavlink_parse_char(chan, byte, &msg))
526+ * if (mavlink_parse_char(chan, byte, &msg, &status ))
507527 * {
508528 * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
509529 * }
0 commit comments