Classes | Macros | Typedefs | Functions
mavlink_msg_memory_vect.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_memory_vect_t
 

Macros

#define MAVLINK_MESSAGE_INFO_MEMORY_VECT
 
#define MAVLINK_MSG_ID_249_CRC   204
 
#define MAVLINK_MSG_ID_249_LEN   36
 
#define MAVLINK_MSG_ID_MEMORY_VECT   249
 
#define MAVLINK_MSG_ID_MEMORY_VECT_CRC   204
 
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN   36
 
#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN   32
 

Typedefs

typedef struct __mavlink_memory_vect_t mavlink_memory_vect_t
 

Functions

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. More...
 
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. More...
 
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. More...
 
static uint16_t mavlink_msg_memory_vect_get_address (const mavlink_message_t *msg)
 Send a memory_vect message. More...
 
static uint8_t mavlink_msg_memory_vect_get_type (const mavlink_message_t *msg)
 Get field type from memory_vect message. More...
 
static uint16_t mavlink_msg_memory_vect_get_value (const mavlink_message_t *msg, int8_t *value)
 Get field value from memory_vect message. More...
 
static uint8_t mavlink_msg_memory_vect_get_ver (const mavlink_message_t *msg)
 Get field ver from memory_vect message. More...
 
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. More...
 
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. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_MEMORY_VECT
Value:
{ \
"MEMORY_VECT", \
4, \
{ { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \
{ "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \
{ "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_memory_vect.h.

#define MAVLINK_MSG_ID_249_CRC   204

Definition at line 17 of file mavlink_msg_memory_vect.h.

#define MAVLINK_MSG_ID_249_LEN   36

Definition at line 14 of file mavlink_msg_memory_vect.h.

#define MAVLINK_MSG_ID_MEMORY_VECT   249

Definition at line 3 of file mavlink_msg_memory_vect.h.

#define MAVLINK_MSG_ID_MEMORY_VECT_CRC   204

Definition at line 16 of file mavlink_msg_memory_vect.h.

#define MAVLINK_MSG_ID_MEMORY_VECT_LEN   36

Definition at line 13 of file mavlink_msg_memory_vect.h.

#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN   32

Definition at line 19 of file mavlink_msg_memory_vect.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_memory_vect_decode ( const mavlink_message_t *  msg,
mavlink_memory_vect_t memory_vect 
)
inlinestatic

Decode a memory_vect message into a struct.

Parameters
msgThe message to decode
memory_vectC-struct to decode the message contents into

Definition at line 263 of file mavlink_msg_memory_vect.h.

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 
)
inlinestatic

Encode a memory_vect struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
memory_vectC-struct to read the message contents from

Definition at line 119 of file mavlink_msg_memory_vect.h.

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 
)
inlinestatic

Encode a memory_vect struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
memory_vectC-struct to read the message contents from

Definition at line 133 of file mavlink_msg_memory_vect.h.

static uint16_t mavlink_msg_memory_vect_get_address ( const mavlink_message_t *  msg)
inlinestatic

Send a memory_vect message.

Parameters
chanMAVLink channel to send the message
addressStarting address of the debug variables
verVersion code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
typeType code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
valueMemory contents at specified address Get field address from memory_vect message
Returns
Starting address of the debug variables

Definition at line 222 of file mavlink_msg_memory_vect.h.

static uint8_t mavlink_msg_memory_vect_get_type ( const mavlink_message_t *  msg)
inlinestatic

Get field type from memory_vect message.

Returns
Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14

Definition at line 242 of file mavlink_msg_memory_vect.h.

static uint16_t mavlink_msg_memory_vect_get_value ( const mavlink_message_t *  msg,
int8_t *  value 
)
inlinestatic

Get field value from memory_vect message.

Returns
Memory contents at specified address

Definition at line 252 of file mavlink_msg_memory_vect.h.

static uint8_t mavlink_msg_memory_vect_get_ver ( const mavlink_message_t *  msg)
inlinestatic

Get field ver from memory_vect message.

Returns
Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below

Definition at line 232 of file mavlink_msg_memory_vect.h.

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 
)
inlinestatic

Pack a memory_vect message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
addressStarting address of the debug variables
verVersion code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
typeType code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
valueMemory contents at specified address
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_memory_vect.h.

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 
)
inlinestatic

Pack a memory_vect message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
addressStarting address of the debug variables
verVersion code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
typeType code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
valueMemory contents at specified address
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 83 of file mavlink_msg_memory_vect.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51