Go to the source code of this file.
|
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...
|
|
#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 |
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
-
msg | The message to decode |
named_value_int | C-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_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
named_value_int | C-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_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
named_value_int | C-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 |
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
-
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp (milliseconds since system boot) |
name | Name of the debug variable |
value | Signed 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 |
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_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
time_boot_ms | Timestamp (milliseconds since system boot) |
name | Name of the debug variable |
value | Signed 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_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
time_boot_ms | Timestamp (milliseconds since system boot) |
name | Name of the debug variable |
value | Signed 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.