#include "string.h"
#include "checksum.h"
#include "mavlink_types.h"
#include "mavlink_conversions.h"
#include <stdio.h>
#include "mavlink_sha256.h"
Go to the source code of this file.
Classes | |
union | __mavlink_bitfield |
Defines | |
#define | MAVLINK_HAVE_EXPECTED_MESSAGE_LENGTH |
#define | MAVLINK_HELPER |
Functions | |
static void | _mav_parse_error (mavlink_status_t *status) |
MAVLINK_HELPER uint8_t | mavlink_expected_message_length (const mavlink_message_t *msg) |
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) |
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel. | |
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) |
Finalize a MAVLink message with channel assignment. | |
MAVLINK_HELPER uint8_t | mavlink_frame_char (uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status) |
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) |
MAVLINK_HELPER mavlink_message_t * | mavlink_get_channel_buffer (uint8_t chan) |
MAVLINK_HELPER mavlink_status_t * | mavlink_get_channel_status (uint8_t chan) |
MAVLINK_HELPER uint8_t | mavlink_get_crc_extra (const mavlink_message_t *msg) |
MAVLINK_HELPER const mavlink_msg_entry_t * | mavlink_get_msg_entry (uint32_t msgid) |
MAVLINK_HELPER uint16_t | mavlink_msg_to_send_buffer (uint8_t *buf, const mavlink_message_t *msg) |
Pack a message to send it over a serial byte stream. | |
MAVLINK_HELPER uint8_t | mavlink_parse_char (uint8_t chan, uint8_t c, mavlink_message_t *r_message, mavlink_status_t *r_mavlink_status) |
MAVLINK_HELPER void | mavlink_reset_channel_status (uint8_t chan) |
Reset the status of a channel. | |
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]) |
create 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) |
check a signature block for a packet | |
MAVLINK_HELPER void | mavlink_start_checksum (mavlink_message_t *msg) |
MAVLINK_HELPER void | mavlink_update_checksum (mavlink_message_t *msg, uint8_t c) |
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) |
Put a bitfield of length 1-32 bit into the buffer. |
Definition at line 467 of file include_v2.0/mavlink_helpers.h.
#define MAVLINK_HELPER |
Definition at line 11 of file include_v2.0/mavlink_helpers.h.
static void _mav_parse_error | ( | mavlink_status_t * | status | ) | [inline, static] |
Definition at line 257 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER uint8_t mavlink_expected_message_length | ( | const mavlink_message_t * | msg | ) |
Definition at line 468 of file include_v2.0/mavlink_helpers.h.
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 | ||
) |
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition at line 251 of file include_v2.0/mavlink_helpers.h.
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 | ||
) |
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.
msg | Message to finalize |
system_id | Id of the sending (this) system, 1-127 |
length | Message length |
Definition at line 185 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER uint8_t mavlink_frame_char | ( | uint8_t | chan, |
uint8_t | c, | ||
mavlink_message_t * | r_message, | ||
mavlink_status_t * | r_mavlink_status | ||
) |
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 *returnMsg and the channel's status is copied into *returnStats.
chan | ID of the current channel. This allows to parse different channels with this function. a channel is not a physical message channel like a serial port, but a logic partition of the communication streams in this case. 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 |
c | The char to parse |
returnMsg | NULL if no message could be decoded, the message data else |
returnStats | if a message was decoded, this is filled with the channel's stats |
A typical use scenario of this function call is:
#include <mavlink.h> mavlink_message_t msg; int chan = 0; while(serial.bytesAvailable > 0) { uint8_t byte = serial.getNextByte(); if (mavlink_frame_char(chan, byte, &msg) != 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); } }
Definition at line 806 of file include_v2.0/mavlink_helpers.h.
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 | ||
) |
This is a varient 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
rxmsg | parsing message buffer |
status | parsing starus buffer |
c | The char to parse |
returnMsg | NULL if no message could be decoded, the message data else |
returnStats | if a message was decoded, this is filled with the channel's stats |
A typical use scenario of this function call is:
#include <mavlink.h> mavlink_message_t msg; int chan = 0; while(serial.bytesAvailable > 0) { uint8_t byte = serial.getNextByte(); if (mavlink_frame_char(chan, byte, &msg) != 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); } }
Definition at line 508 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer | ( | uint8_t | chan | ) |
Definition at line 36 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status | ( | uint8_t | chan | ) |
Definition at line 20 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER uint8_t mavlink_get_crc_extra | ( | const mavlink_message_t * | msg | ) |
Definition at line 458 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER const mavlink_msg_entry_t* mavlink_get_msg_entry | ( | uint32_t | msgid | ) |
Definition at line 427 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer | ( | uint8_t * | buf, |
const mavlink_message_t * | msg | ||
) |
Pack a message to send it over a serial byte stream.
Definition at line 363 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER uint8_t mavlink_parse_char | ( | uint8_t | chan, |
uint8_t | c, | ||
mavlink_message_t * | r_message, | ||
mavlink_status_t * | r_mavlink_status | ||
) |
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 *returnMsg and the channel's status is copied into *returnStats.
chan | ID of the current channel. This allows to parse different channels with this function. a channel is not a physical message channel like a serial port, but a logic partition of the communication streams in this case. 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 |
c | The char to parse |
returnMsg | NULL if no message could be decoded, the message data else |
returnStats | if a message was decoded, this is filled with the channel's stats |
A typical use scenario of this function call is:
#include <mavlink.h> mavlink_message_t msg; int chan = 0; while(serial.bytesAvailable > 0) { uint8_t byte = serial.getNextByte(); if (mavlink_parse_char(chan, byte, &msg)) { printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); } }
< The currently decoded message
< The current decode status
Definition at line 856 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER void mavlink_reset_channel_status | ( | uint8_t | chan | ) |
Reset the status of a channel.
Definition at line 52 of file include_v2.0/mavlink_helpers.h.
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] | ||
) |
create a signature block for a packet
Definition at line 61 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER bool mavlink_signature_check | ( | mavlink_signing_t * | signing, |
mavlink_signing_streams_t * | signing_streams, | ||
const mavlink_message_t * | msg | ||
) |
check a signature block for a packet
Definition at line 94 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER void mavlink_start_checksum | ( | mavlink_message_t * | msg | ) |
Definition at line 414 of file include_v2.0/mavlink_helpers.h.
MAVLINK_HELPER void mavlink_update_checksum | ( | mavlink_message_t * | msg, |
uint8_t | c | ||
) |
Definition at line 419 of file include_v2.0/mavlink_helpers.h.
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 | ||
) |
Put a bitfield of length 1-32 bit into the buffer.
b | the value to add, will be encoded in the bitfield |
bits | number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. |
packet_index | the position in the packet (the index of the first byte to use) |
bit_index | the position in the byte (the index of the first bit to use) |
buffer | packet buffer to write into |
Definition at line 888 of file include_v2.0/mavlink_helpers.h.