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

Go to the source code of this file.

Defines

#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)   (const char)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset)   (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset)   (const 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

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)
static uint16_t mavlink_msg_get_send_buffer_length (const mavlink_message_t *msg)
 Get the required buffer size for this message.

Define 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 243 of file include_v2.0/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 209 of file include_v2.0/protocol.h.

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

Definition at line 138 of file include_v2.0/protocol.h.

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

Definition at line 148 of file include_v2.0/protocol.h.

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

Definition at line 147 of file include_v2.0/protocol.h.

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

Definition at line 142 of file include_v2.0/protocol.h.

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

Definition at line 144 of file include_v2.0/protocol.h.

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

Definition at line 146 of file include_v2.0/protocol.h.

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

Definition at line 137 of file include_v2.0/protocol.h.

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

Definition at line 141 of file include_v2.0/protocol.h.

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

Definition at line 143 of file include_v2.0/protocol.h.

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

Definition at line 145 of file include_v2.0/protocol.h.

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

Definition at line 136 of file include_v2.0/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 306 of file include_v2.0/protocol.h.

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

Definition at line 238 of file include_v2.0/protocol.h.

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

Definition at line 239 of file include_v2.0/protocol.h.

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

Definition at line 240 of file include_v2.0/protocol.h.

#define MAVLINK_ASSERT (   x)

Definition at line 26 of file include_v2.0/protocol.h.

#define MAVLINK_AVOID_GCC_STACK_BUG   defined(__GNUC__)

Definition at line 22 of file include_v2.0/protocol.h.

#define MAVLINK_END_UART_SEND (   chan,
  length 
)

Definition at line 34 of file include_v2.0/protocol.h.

#define MAVLINK_HELPER   static inline

Definition at line 75 of file include_v2.0/protocol.h.

Definition at line 14 of file include_v2.0/protocol.h.

#define MAVLINK_STACK_BUFFER   0

Definition at line 18 of file include_v2.0/protocol.h.

#define MAVLINK_START_UART_SEND (   chan,
  length 
)

Definition at line 30 of file include_v2.0/protocol.h.


Function Documentation

static void _mav_put_char_array ( char *  buf,
uint8_t  wire_offset,
const char *  b,
uint8_t  array_length 
) [inline, static]

Definition at line 184 of file include_v2.0/protocol.h.

static void _mav_put_int8_t_array ( char *  buf,
uint8_t  wire_offset,
const int8_t *  b,
uint8_t  array_length 
) [inline, static]

Definition at line 202 of file include_v2.0/protocol.h.

static void _mav_put_uint8_t_array ( char *  buf,
uint8_t  wire_offset,
const uint8_t *  b,
uint8_t  array_length 
) [inline, static]

Definition at line 193 of file include_v2.0/protocol.h.

static uint16_t _MAV_RETURN_char_array ( const mavlink_message_t msg,
char *  value,
uint8_t  array_length,
uint8_t  wire_offset 
) [inline, static]

Definition at line 284 of file include_v2.0/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 
) [inline, static]

Definition at line 298 of file include_v2.0/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 
) [inline, static]

Definition at line 291 of file include_v2.0/protocol.h.

static void byte_swap_2 ( char *  dst,
const char *  src 
) [inline, static]

Definition at line 94 of file include_v2.0/protocol.h.

static void byte_swap_4 ( char *  dst,
const char *  src 
) [inline, static]

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

static void byte_swap_8 ( char *  dst,
const char *  src 
) [inline, static]

Definition at line 106 of file include_v2.0/protocol.h.

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

Definition at line 172 of file include_v2.0/protocol.h.

static uint16_t mavlink_msg_get_send_buffer_length ( const mavlink_message_t msg) [inline, static]

Get the required buffer size for this message.

Definition at line 84 of file include_v2.0/protocol.h.



mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57