Classes | Macros | Typedefs | Functions
mavlink_msg_named_value_int.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_named_value_int_t
 

Macros

#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT
 
#define MAVLINK_MSG_ID_252_CRC   44
 
#define MAVLINK_MSG_ID_252_LEN   18
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT   252
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC   44
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN   18
 
#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN   10
 

Typedefs

typedef struct __mavlink_named_value_int_t mavlink_named_value_int_t
 

Functions

static void mavlink_msg_named_value_int_decode (const mavlink_message_t *msg, mavlink_named_value_int_t *named_value_int)
 Decode a named_value_int message into a struct. More...
 
static uint16_t mavlink_msg_named_value_int_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_named_value_int_t *named_value_int)
 Encode a named_value_int struct. More...
 
static uint16_t mavlink_msg_named_value_int_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_named_value_int_t *named_value_int)
 Encode a named_value_int struct on a channel. More...
 
static uint16_t mavlink_msg_named_value_int_get_name (const mavlink_message_t *msg, char *name)
 Get field name from named_value_int message. More...
 
static uint32_t mavlink_msg_named_value_int_get_time_boot_ms (const mavlink_message_t *msg)
 Send a named_value_int message. More...
 
static int32_t mavlink_msg_named_value_int_get_value (const mavlink_message_t *msg)
 Get field value from named_value_int message. More...
 
static uint16_t mavlink_msg_named_value_int_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, const char *name, int32_t value)
 Pack a named_value_int message. More...
 
static uint16_t mavlink_msg_named_value_int_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, const char *name, int32_t value)
 Pack a named_value_int message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT
Value:
{ \
"NAMED_VALUE_INT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 20 of file mavlink_msg_named_value_int.h.

#define MAVLINK_MSG_ID_252_CRC   44

Definition at line 16 of file mavlink_msg_named_value_int.h.

#define MAVLINK_MSG_ID_252_LEN   18

Definition at line 13 of file mavlink_msg_named_value_int.h.

#define MAVLINK_MSG_ID_NAMED_VALUE_INT   252

Definition at line 3 of file mavlink_msg_named_value_int.h.

#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC   44

Definition at line 15 of file mavlink_msg_named_value_int.h.

#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN   18

Definition at line 12 of file mavlink_msg_named_value_int.h.

#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN   10

Definition at line 18 of file mavlink_msg_named_value_int.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_named_value_int_decode ( const mavlink_message_t *  msg,
mavlink_named_value_int_t named_value_int 
)
inlinestatic

Decode a named_value_int message into a struct.

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

Definition at line 240 of file mavlink_msg_named_value_int.h.

static uint16_t mavlink_msg_named_value_int_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_named_value_int_t named_value_int 
)
inlinestatic

Encode a named_value_int 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
named_value_intC-struct to read the message contents from

Definition at line 111 of file mavlink_msg_named_value_int.h.

static uint16_t mavlink_msg_named_value_int_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_named_value_int_t named_value_int 
)
inlinestatic

Encode a named_value_int 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
named_value_intC-struct to read the message contents from

Definition at line 125 of file mavlink_msg_named_value_int.h.

static uint16_t mavlink_msg_named_value_int_get_name ( const mavlink_message_t *  msg,
char *  name 
)
inlinestatic

Get field name from named_value_int message.

Returns
Name of the debug variable

Definition at line 219 of file mavlink_msg_named_value_int.h.

static uint32_t mavlink_msg_named_value_int_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a named_value_int message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
nameName of the debug variable
valueSigned integer value Get field time_boot_ms from named_value_int message
Returns
Timestamp (milliseconds since system boot)

Definition at line 209 of file mavlink_msg_named_value_int.h.

static int32_t mavlink_msg_named_value_int_get_value ( const mavlink_message_t *  msg)
inlinestatic

Get field value from named_value_int message.

Returns
Signed integer value

Definition at line 229 of file mavlink_msg_named_value_int.h.

static uint16_t mavlink_msg_named_value_int_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
const char *  name,
int32_t  value 
)
inlinestatic

Pack a named_value_int 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
time_boot_msTimestamp (milliseconds since system boot)
nameName of the debug variable
valueSigned integer value
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 41 of file mavlink_msg_named_value_int.h.

static uint16_t mavlink_msg_named_value_int_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
const char *  name,
int32_t  value 
)
inlinestatic

Pack a named_value_int 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
time_boot_msTimestamp (milliseconds since system boot)
nameName of the debug variable
valueSigned integer value
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 77 of file mavlink_msg_named_value_int.h.



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