Classes | Macros | Functions
include_v2.0/mavlink_helpers.h File Reference
#include "string.h"
#include "checksum.h"
#include "mavlink_types.h"
#include "mavlink_conversions.h"
#include <stdio.h>
#include "mavlink_sha256.h"
Include dependency graph for include_v2.0/mavlink_helpers.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

union  __mavlink_bitfield
 

Macros

#define MAVLINK_HAVE_EXPECTED_MESSAGE_LENGTH
 
#define MAVLINK_HELPER
 

Functions

static void _mav_parse_error (mavlink_status_t *status)
 
MAVLINK_HELPER uint8_t _mav_trim_payload (const char *payload, uint8_t length)
 
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. More...
 
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)
 Finalize a MAVLink message with channel assignment. More...
 
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_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_tmavlink_get_channel_buffer (uint8_t chan)
 
MAVLINK_HELPER mavlink_status_tmavlink_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_tmavlink_get_msg_entry (uint32_t msgid)
 
MAVLINK_HELPER unsigned int mavlink_get_proto_version (uint8_t chan)
 
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. More...
 
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. More...
 
MAVLINK_HELPER void mavlink_set_proto_version (uint8_t chan, unsigned int version)
 
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 More...
 
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 More...
 
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. More...
 

Macro Definition Documentation

#define MAVLINK_HAVE_EXPECTED_MESSAGE_LENGTH

Definition at line 530 of file include_v2.0/mavlink_helpers.h.

#define MAVLINK_HELPER

Definition at line 10 of file include_v2.0/mavlink_helpers.h.

Function Documentation

static void _mav_parse_error ( mavlink_status_t status)
inlinestatic

Definition at line 281 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER uint8_t _mav_trim_payload ( const char *  payload,
uint8_t  length 
)

return new packet length for trimming payload of any trailing zero bytes. Used in MAVLink2 to give simple support for variable length arrays.

Definition at line 99 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER uint8_t mavlink_expected_message_length ( const mavlink_message_t msg)

Definition at line 531 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 275 of file include_v2.0/mavlink_helpers.h.

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 
)

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.

Parameters
msgMessage to finalize
system_idId of the sending (this) system, 1-127
lengthMessage length

Definition at line 202 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 
)

Definition at line 265 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 *r_message and the channel's status is copied into *r_mavlink_status.

Parameters
chanID 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
cThe char to parse
r_messageNULL if no message could be decoded, otherwise the message data
r_mavlink_statusif a message was decoded, this is filled with the channel's stats
Returns
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:

1 #include <mavlink.h>
2 
3 mavlink_status_t status;
4 mavlink_message_t msg;
5 int chan = 0;
6 
7 
8 while(serial.bytesAvailable > 0)
9 {
10  uint8_t byte = serial.getNextByte();
11  if (mavlink_frame_char(chan, byte, &msg, &status) != MAVLINK_FRAMING_INCOMPLETE)
12  {
13  printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
14  }
15 }

Definition at line 879 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 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

Parameters
rxmsgparsing message buffer
statusparsing status buffer
cThe char to parse
r_messageNULL if no message could be decoded, otherwise the message data
r_mavlink_statusif a message was decoded, this is filled with the channel's stats
Returns
0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC

Definition at line 551 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer ( uint8_t  chan)

Definition at line 39 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status ( uint8_t  chan)

Definition at line 23 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER uint8_t mavlink_get_crc_extra ( const mavlink_message_t msg)

Definition at line 521 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER const mavlink_msg_entry_t* mavlink_get_msg_entry ( uint32_t  msgid)

Return message entry data for msgid.

Note
user of MAVLink library should provide implementation for this function. Use mavlink::<dialect-name>::MESSAGE_ENTRIES array to make hash map.
Returns
nullptr if message is unknown

Definition at line 489 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER unsigned int mavlink_get_proto_version ( uint8_t  chan)

Get the protocol version

Returns
1 for v1, 2 for v2

Definition at line 906 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 418 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 *r_message and the channel's status is copied into *r_mavlink_status.

Parameters
chanID 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
cThe char to parse
r_messageNULL if no message could be decoded, otherwise the message data
r_mavlink_statusif a message was decoded, this is filled with the channel's stats
Returns
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:

1 #include <mavlink.h>
2 
3 mavlink_status_t status;
4 mavlink_message_t msg;
5 int chan = 0;
6 
7 
8 while(serial.bytesAvailable > 0)
9 {
10  uint8_t byte = serial.getNextByte();
11  if (mavlink_parse_char(chan, byte, &msg, &status))
12  {
13  printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
14  }
15 }

< The currently decoded message

< The current decode status

Definition at line 957 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 55 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER void mavlink_set_proto_version ( uint8_t  chan,
unsigned int  version 
)

Set the protocol version

Definition at line 891 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 64 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 110 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER void mavlink_start_checksum ( mavlink_message_t msg)

Definition at line 471 of file include_v2.0/mavlink_helpers.h.

MAVLINK_HELPER void mavlink_update_checksum ( mavlink_message_t msg,
uint8_t  c 
)

Definition at line 478 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.

Parameters
bthe value to add, will be encoded in the bitfield
bitsnumber of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
packet_indexthe position in the packet (the index of the first byte to use)
bit_indexthe position in the byte (the index of the first bit to use)
bufferpacket buffer to write into
Returns
new position of the last used byte in the buffer

Definition at line 989 of file include_v2.0/mavlink_helpers.h.



mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02