3 #define MAVLINK_MSG_ID_MEMORY_VECT 249 13 #define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 14 #define MAVLINK_MSG_ID_249_LEN 36 16 #define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 17 #define MAVLINK_MSG_ID_249_CRC 204 19 #define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 21 #define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ 24 { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ 25 { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ 26 { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ 27 { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ 47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 84 mavlink_message_t* msg,
87 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 104 #if MAVLINK_CRC_EXTRA 147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 157 #if MAVLINK_CRC_EXTRA 168 #if MAVLINK_CRC_EXTRA 176 #if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN 186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 187 char *buf = (
char *)msgbuf;
192 #if MAVLINK_CRC_EXTRA 203 #if MAVLINK_CRC_EXTRA 224 return _MAV_RETURN_uint16_t(msg, 0);
265 #if MAVLINK_NEED_BYTE_SWAP static uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value, uint8_t array_length, uint8_t wire_offset)
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_memory_vect_t *memory_vect)
Encode a memory_vect struct on a channel.
static uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
Pack a memory_vect message.
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.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t *msg, int8_t *value)
Get field value from memory_vect message.
#define _MAV_PAYLOAD(msg)
struct __mavlink_memory_vect_t mavlink_memory_vect_t
static uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_memory_vect_t *memory_vect)
Encode a memory_vect struct.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t *msg)
Get field type from memory_vect message.
#define MAVLINK_MSG_ID_MEMORY_VECT_CRC
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN
#define _mav_put_uint16_t(buf, wire_offset, b)
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.
#define MAVLINK_MSG_ID_MEMORY_VECT
static uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
Pack a memory_vect message on a channel.
static void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
static uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t *msg)
Send a memory_vect message.
static void mavlink_msg_memory_vect_decode(const mavlink_message_t *msg, mavlink_memory_vect_t *memory_vect)
Decode a memory_vect message into a struct.
static uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t *msg)
Get field ver from memory_vect message.