Go to the source code of this file.
Classes | |
struct | __mavlink_named_value_float_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT |
#define | MAVLINK_MSG_ID_251_CRC 170 |
#define | MAVLINK_MSG_ID_251_LEN 18 |
#define | MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 |
#define | MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 |
#define | MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 |
#define | MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 |
Typedefs | |
typedef struct __mavlink_named_value_float_t | mavlink_named_value_float_t |
Functions | |
static void | mavlink_msg_named_value_float_decode (const mavlink_message_t *msg, mavlink_named_value_float_t *named_value_float) |
Decode a named_value_float message into a struct. | |
static uint16_t | mavlink_msg_named_value_float_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_named_value_float_t *named_value_float) |
Encode a named_value_float struct. | |
static uint16_t | mavlink_msg_named_value_float_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_named_value_float_t *named_value_float) |
Encode a named_value_float struct on a channel. | |
static uint16_t | mavlink_msg_named_value_float_get_name (const mavlink_message_t *msg, char *name) |
Get field name from named_value_float message. | |
static uint32_t | mavlink_msg_named_value_float_get_time_boot_ms (const mavlink_message_t *msg) |
Send a named_value_float message. | |
static float | mavlink_msg_named_value_float_get_value (const mavlink_message_t *msg) |
Get field value from named_value_float message. | |
static uint16_t | mavlink_msg_named_value_float_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, const char *name, float value) |
Pack a named_value_float message. | |
static uint16_t | mavlink_msg_named_value_float_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, float value) |
Pack a named_value_float message on a channel. |
{ \ "NAMED_VALUE_FLOAT", \ 3, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ } \ }
Definition at line 20 of file mavlink_msg_named_value_float.h.
#define MAVLINK_MSG_ID_251_CRC 170 |
Definition at line 16 of file mavlink_msg_named_value_float.h.
#define MAVLINK_MSG_ID_251_LEN 18 |
Definition at line 13 of file mavlink_msg_named_value_float.h.
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 |
Definition at line 3 of file mavlink_msg_named_value_float.h.
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 |
Definition at line 15 of file mavlink_msg_named_value_float.h.
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 |
Definition at line 12 of file mavlink_msg_named_value_float.h.
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 |
Definition at line 18 of file mavlink_msg_named_value_float.h.
typedef struct __mavlink_named_value_float_t mavlink_named_value_float_t |
static void mavlink_msg_named_value_float_decode | ( | const mavlink_message_t * | msg, |
mavlink_named_value_float_t * | named_value_float | ||
) | [inline, static] |
Decode a named_value_float message into a struct.
msg | The message to decode |
named_value_float | C-struct to decode the message contents into |
Definition at line 240 of file mavlink_msg_named_value_float.h.
static uint16_t mavlink_msg_named_value_float_encode | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
const mavlink_named_value_float_t * | named_value_float | ||
) | [inline, static] |
Encode a named_value_float struct.
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_float | C-struct to read the message contents from |
Definition at line 111 of file mavlink_msg_named_value_float.h.
static uint16_t mavlink_msg_named_value_float_encode_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
const mavlink_named_value_float_t * | named_value_float | ||
) | [inline, static] |
Encode a named_value_float struct on a channel.
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_float | C-struct to read the message contents from |
Definition at line 125 of file mavlink_msg_named_value_float.h.
static uint16_t mavlink_msg_named_value_float_get_name | ( | const mavlink_message_t * | msg, |
char * | name | ||
) | [inline, static] |
Get field name from named_value_float message.
Definition at line 219 of file mavlink_msg_named_value_float.h.
static uint32_t mavlink_msg_named_value_float_get_time_boot_ms | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a named_value_float message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp (milliseconds since system boot) |
name | Name of the debug variable |
value | Floating point value Get field time_boot_ms from named_value_float message |
Definition at line 209 of file mavlink_msg_named_value_float.h.
static float mavlink_msg_named_value_float_get_value | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field value from named_value_float message.
Definition at line 229 of file mavlink_msg_named_value_float.h.
static uint16_t mavlink_msg_named_value_float_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
const char * | name, | ||
float | value | ||
) | [inline, static] |
Pack a named_value_float message.
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 | Floating point value |
Definition at line 41 of file mavlink_msg_named_value_float.h.
static uint16_t mavlink_msg_named_value_float_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, | ||
float | value | ||
) | [inline, static] |
Pack a named_value_float message on a channel.
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 | Floating point value |
Definition at line 77 of file mavlink_msg_named_value_float.h.