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 | |
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. More... | |
#define _MAV_MSG_RETURN_TYPE | ( | TYPE, | |
SIZE | |||
) |
Definition at line 247 of file include_v1.0/protocol.h.
#define _MAV_PUT_ARRAY | ( | TYPE, | |
V | |||
) |
Definition at line 213 of file include_v1.0/protocol.h.
#define _mav_put_char | ( | buf, | |
wire_offset, | |||
b | |||
) | buf[wire_offset] = b |
Definition at line 142 of file include_v1.0/protocol.h.
#define _mav_put_double | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_8(&buf[wire_offset], (const char *)&b) |
Definition at line 152 of file include_v1.0/protocol.h.
#define _mav_put_float | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_4(&buf[wire_offset], (const char *)&b) |
Definition at line 151 of file include_v1.0/protocol.h.
#define _mav_put_int16_t | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_2(&buf[wire_offset], (const char *)&b) |
Definition at line 146 of file include_v1.0/protocol.h.
#define _mav_put_int32_t | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_4(&buf[wire_offset], (const char *)&b) |
Definition at line 148 of file include_v1.0/protocol.h.
#define _mav_put_int64_t | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_8(&buf[wire_offset], (const char *)&b) |
Definition at line 150 of file include_v1.0/protocol.h.
#define _mav_put_int8_t | ( | buf, | |
wire_offset, | |||
b | |||
) | buf[wire_offset] = (int8_t)b |
Definition at line 141 of file include_v1.0/protocol.h.
#define _mav_put_uint16_t | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_2(&buf[wire_offset], (const char *)&b) |
Definition at line 145 of file include_v1.0/protocol.h.
#define _mav_put_uint32_t | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_4(&buf[wire_offset], (const char *)&b) |
Definition at line 147 of file include_v1.0/protocol.h.
#define _mav_put_uint64_t | ( | buf, | |
wire_offset, | |||
b | |||
) | byte_swap_8(&buf[wire_offset], (const char *)&b) |
Definition at line 149 of file include_v1.0/protocol.h.
#define _mav_put_uint8_t | ( | buf, | |
wire_offset, | |||
b | |||
) | buf[wire_offset] = (uint8_t)b |
Definition at line 140 of file include_v1.0/protocol.h.
#define _MAV_RETURN_ARRAY | ( | TYPE, | |
V | |||
) |
Definition at line 310 of file include_v1.0/protocol.h.
#define _MAV_RETURN_char | ( | msg, | |
wire_offset | |||
) | (char)_MAV_PAYLOAD(msg)[wire_offset] |
Definition at line 242 of file include_v1.0/protocol.h.
#define _MAV_RETURN_int8_t | ( | msg, | |
wire_offset | |||
) | (int8_t)_MAV_PAYLOAD(msg)[wire_offset] |
Definition at line 243 of file include_v1.0/protocol.h.
#define _MAV_RETURN_uint8_t | ( | msg, | |
wire_offset | |||
) | (uint8_t)_MAV_PAYLOAD(msg)[wire_offset] |
Definition at line 244 of file include_v1.0/protocol.h.
#define MAVLINK_ASSERT | ( | x | ) |
Definition at line 26 of file include_v1.0/protocol.h.
#define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) |
Definition at line 22 of file include_v1.0/protocol.h.
#define MAVLINK_END_UART_SEND | ( | chan, | |
length | |||
) |
Definition at line 34 of file include_v1.0/protocol.h.
#define MAVLINK_HELPER static inline |
Definition at line 84 of file include_v1.0/protocol.h.
#define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) |
Definition at line 14 of file include_v1.0/protocol.h.
#define MAVLINK_STACK_BUFFER 0 |
Definition at line 18 of file include_v1.0/protocol.h.
#define MAVLINK_START_UART_SEND | ( | chan, | |
length | |||
) |
Definition at line 30 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 188 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 206 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 197 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 288 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 302 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 295 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 98 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 103 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 110 of file include_v1.0/protocol.h.
|
inlinestatic |
Definition at line 176 of file include_v1.0/protocol.h.
|
inlinestatic |
Get the required buffer size for this message.
Definition at line 92 of file include_v1.0/protocol.h.