Macros | Functions
include_v0.9/protocol.h File Reference
#include "string.h"
#include "mavlink_types.h"
#include "mavlink_helpers.h"
Include dependency graph for include_v0.9/protocol.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Macros

#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE)
 
#define _MAV_PUT_ARRAY(TYPE, V)
 
#define _mav_put_char(buf, wire_offset, b)   buf[wire_offset] = b
 
#define _mav_put_double(buf, wire_offset, b)   byte_swap_8(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_float(buf, wire_offset, b)   byte_swap_4(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_int16_t(buf, wire_offset, b)   byte_swap_2(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_int32_t(buf, wire_offset, b)   byte_swap_4(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_int64_t(buf, wire_offset, b)   byte_swap_8(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_int8_t(buf, wire_offset, b)   buf[wire_offset] = (int8_t)b
 
#define _mav_put_uint16_t(buf, wire_offset, b)   byte_swap_2(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_uint32_t(buf, wire_offset, b)   byte_swap_4(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_uint64_t(buf, wire_offset, b)   byte_swap_8(&buf[wire_offset], (const char *)&b)
 
#define _mav_put_uint8_t(buf, wire_offset, b)   buf[wire_offset] = (uint8_t)b
 
#define _MAV_RETURN_ARRAY(TYPE, V)
 
#define _MAV_RETURN_char(msg, wire_offset)   (char)_MAV_PAYLOAD(msg)[wire_offset]
 
#define _MAV_RETURN_int8_t(msg, wire_offset)   (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
 
#define _MAV_RETURN_uint8_t(msg, wire_offset)   (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
 
#define MAVLINK_ASSERT(x)
 
#define MAVLINK_AVOID_GCC_STACK_BUG   defined(__GNUC__)
 
#define MAVLINK_END_UART_SEND(chan, length)
 
#define MAVLINK_HELPER   static inline
 
#define MAVLINK_NEED_BYTE_SWAP   (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
 
#define MAVLINK_STACK_BUFFER   0
 
#define MAVLINK_START_UART_SEND(chan, length)
 

Functions

MAVLINK_HELPER void _mav_finalize_message_chan_send (mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
 
static void _mav_put_char_array (char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
 
static void _mav_put_int8_t_array (char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
 
static void _mav_put_uint8_t_array (char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
 
static uint16_t _MAV_RETURN_char_array (const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
 
static uint16_t _MAV_RETURN_int8_t_array (const mavlink_message_t *msg, int8_t *value, uint8_t array_length, uint8_t wire_offset)
 
static uint16_t _MAV_RETURN_uint8_t_array (const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
 
static void byte_swap_2 (char *dst, const char *src)
 
static void byte_swap_4 (char *dst, const char *src)
 
static void byte_swap_8 (char *dst, const char *src)
 
static void mav_array_memcpy (void *dest, const void *src, size_t n)
 
MAVLINK_HELPER uint16_t mavlink_finalize_message (mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
 Finalize a MAVLink message with MAVLINK_COMM_0 as default channel. 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 length)
 Finalize a MAVLink message with channel assignment. More...
 
MAVLINK_HELPER mavlink_status_tmavlink_get_channel_status (uint8_t chan)
 
static uint16_t mavlink_msg_get_send_buffer_length (const mavlink_message_t *msg)
 Get the required buffer size for this message. More...
 
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer (uint8_t *buffer, 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_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 _MAV_MSG_RETURN_TYPE (   TYPE,
  SIZE 
)
Value:
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }

Definition at line 231 of file include_v0.9/protocol.h.

#define _MAV_PUT_ARRAY (   TYPE,
 
)
Value:
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
if (b == NULL) { \
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
} else { \
uint16_t i; \
for (i=0; i<array_length; i++) { \
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
} \
} \
}

Definition at line 197 of file include_v0.9/protocol.h.

#define _mav_put_char (   buf,
  wire_offset,
 
)    buf[wire_offset] = b

Definition at line 126 of file include_v0.9/protocol.h.

#define _mav_put_double (   buf,
  wire_offset,
 
)    byte_swap_8(&buf[wire_offset], (const char *)&b)

Definition at line 136 of file include_v0.9/protocol.h.

#define _mav_put_float (   buf,
  wire_offset,
 
)    byte_swap_4(&buf[wire_offset], (const char *)&b)

Definition at line 135 of file include_v0.9/protocol.h.

#define _mav_put_int16_t (   buf,
  wire_offset,
 
)    byte_swap_2(&buf[wire_offset], (const char *)&b)

Definition at line 130 of file include_v0.9/protocol.h.

#define _mav_put_int32_t (   buf,
  wire_offset,
 
)    byte_swap_4(&buf[wire_offset], (const char *)&b)

Definition at line 132 of file include_v0.9/protocol.h.

#define _mav_put_int64_t (   buf,
  wire_offset,
 
)    byte_swap_8(&buf[wire_offset], (const char *)&b)

Definition at line 134 of file include_v0.9/protocol.h.

#define _mav_put_int8_t (   buf,
  wire_offset,
 
)    buf[wire_offset] = (int8_t)b

Definition at line 125 of file include_v0.9/protocol.h.

#define _mav_put_uint16_t (   buf,
  wire_offset,
 
)    byte_swap_2(&buf[wire_offset], (const char *)&b)

Definition at line 129 of file include_v0.9/protocol.h.

#define _mav_put_uint32_t (   buf,
  wire_offset,
 
)    byte_swap_4(&buf[wire_offset], (const char *)&b)

Definition at line 131 of file include_v0.9/protocol.h.

#define _mav_put_uint64_t (   buf,
  wire_offset,
 
)    byte_swap_8(&buf[wire_offset], (const char *)&b)

Definition at line 133 of file include_v0.9/protocol.h.

#define _mav_put_uint8_t (   buf,
  wire_offset,
 
)    buf[wire_offset] = (uint8_t)b

Definition at line 124 of file include_v0.9/protocol.h.

#define _MAV_RETURN_ARRAY (   TYPE,
 
)
Value:
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
uint16_t i; \
for (i=0; i<array_length; i++) { \
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
} \
return array_length*sizeof(value[0]); \
}

Definition at line 294 of file include_v0.9/protocol.h.

#define _MAV_RETURN_char (   msg,
  wire_offset 
)    (char)_MAV_PAYLOAD(msg)[wire_offset]

Definition at line 226 of file include_v0.9/protocol.h.

#define _MAV_RETURN_int8_t (   msg,
  wire_offset 
)    (int8_t)_MAV_PAYLOAD(msg)[wire_offset]

Definition at line 227 of file include_v0.9/protocol.h.

#define _MAV_RETURN_uint8_t (   msg,
  wire_offset 
)    (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]

Definition at line 228 of file include_v0.9/protocol.h.

#define MAVLINK_ASSERT (   x)

Definition at line 26 of file include_v0.9/protocol.h.

#define MAVLINK_AVOID_GCC_STACK_BUG   defined(__GNUC__)

Definition at line 22 of file include_v0.9/protocol.h.

#define MAVLINK_END_UART_SEND (   chan,
  length 
)

Definition at line 34 of file include_v0.9/protocol.h.

#define MAVLINK_HELPER   static inline

Definition at line 40 of file include_v0.9/protocol.h.

#define MAVLINK_NEED_BYTE_SWAP   (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)

Definition at line 14 of file include_v0.9/protocol.h.

#define MAVLINK_STACK_BUFFER   0

Definition at line 18 of file include_v0.9/protocol.h.

#define MAVLINK_START_UART_SEND (   chan,
  length 
)

Definition at line 30 of file include_v0.9/protocol.h.

Function Documentation

MAVLINK_HELPER void _mav_finalize_message_chan_send ( mavlink_channel_t  chan,
uint8_t  msgid,
const char *  packet,
uint8_t  length 
)
static void _mav_put_char_array ( char *  buf,
uint8_t  wire_offset,
const char *  b,
uint8_t  array_length 
)
inlinestatic

Definition at line 172 of file include_v0.9/protocol.h.

static void _mav_put_int8_t_array ( char *  buf,
uint8_t  wire_offset,
const int8_t *  b,
uint8_t  array_length 
)
inlinestatic

Definition at line 190 of file include_v0.9/protocol.h.

static void _mav_put_uint8_t_array ( char *  buf,
uint8_t  wire_offset,
const uint8_t *  b,
uint8_t  array_length 
)
inlinestatic

Definition at line 181 of file include_v0.9/protocol.h.

static uint16_t _MAV_RETURN_char_array ( const mavlink_message_t msg,
char *  value,
uint8_t  array_length,
uint8_t  wire_offset 
)
inlinestatic

Definition at line 272 of file include_v0.9/protocol.h.

static uint16_t _MAV_RETURN_int8_t_array ( const mavlink_message_t msg,
int8_t *  value,
uint8_t  array_length,
uint8_t  wire_offset 
)
inlinestatic

Definition at line 286 of file include_v0.9/protocol.h.

static uint16_t _MAV_RETURN_uint8_t_array ( const mavlink_message_t msg,
uint8_t *  value,
uint8_t  array_length,
uint8_t  wire_offset 
)
inlinestatic

Definition at line 279 of file include_v0.9/protocol.h.

static void byte_swap_2 ( char *  dst,
const char *  src 
)
inlinestatic

Definition at line 82 of file include_v0.9/protocol.h.

static void byte_swap_4 ( char *  dst,
const char *  src 
)
inlinestatic

Definition at line 87 of file include_v0.9/protocol.h.

static void byte_swap_8 ( char *  dst,
const char *  src 
)
inlinestatic

Definition at line 94 of file include_v0.9/protocol.h.

static void mav_array_memcpy ( void *  dest,
const void *  src,
size_t  n 
)
static

Definition at line 160 of file include_v0.9/protocol.h.

MAVLINK_HELPER uint16_t mavlink_finalize_message ( mavlink_message_t msg,
uint8_t  system_id,
uint8_t  component_id,
uint8_t  length 
)

Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.

Definition at line 89 of file include_v0.9/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  length 
)

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 55 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status ( uint8_t  chan)

Definition at line 15 of file include_v0.9/mavlink_helpers.h.

static uint16_t mavlink_msg_get_send_buffer_length ( const mavlink_message_t msg)
inlinestatic

Get the required buffer size for this message.

Definition at line 76 of file include_v0.9/protocol.h.

MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer ( uint8_t *  buffer,
const mavlink_message_t msg 
)

Pack a message to send it over a serial byte stream.

Definition at line 157 of file include_v0.9/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. Checksum and other failures will be silently ignored.

Parameters
chanID 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
cThe char to barse
returnMsgNULL if no message could be decoded, the message data else
Returns
0 if no message could be decoded, 1 else

A typical use scenario of this function call is:

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

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 }

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 219 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER void mavlink_start_checksum ( mavlink_message_t msg)

Definition at line 173 of file include_v0.9/mavlink_helpers.h.

MAVLINK_HELPER void mavlink_update_checksum ( mavlink_message_t msg,
uint8_t  c 
)

Definition at line 178 of file include_v0.9/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 420 of file include_v0.9/mavlink_helpers.h.



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