mavlink_msg_named_value_float.h 7.57 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE NAMED_VALUE_FLOAT PACKING

3
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_named_value_float_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
lm's avatar
lm committed
8 9
 float value; ///< Floating point value
 char name[10]; ///< Name of the debug variable
James Goppert's avatar
James Goppert committed
10
} mavlink_named_value_float_t;
lm's avatar
lm committed
11

12 13
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18
#define MAVLINK_MSG_ID_251_LEN 18
lm's avatar
lm committed
14

Lorenz Meier's avatar
Lorenz Meier committed
15 16 17
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170
#define MAVLINK_MSG_ID_251_CRC 170

James Goppert's avatar
James Goppert committed
18 19
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10

lm's avatar
lm committed
20 21
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \
	"NAMED_VALUE_FLOAT", \
22
	3, \
lm's avatar
lm committed
23 24 25
	{  { "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) }, \
lm's avatar
lm committed
26 27 28 29
         } \
}


James Goppert's avatar
James Goppert committed
30 31 32 33 34 35
/**
 * @brief Pack a named_value_float message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
36
 * @param time_boot_ms Timestamp (milliseconds since system boot)
James Goppert's avatar
James Goppert committed
37 38 39 40
 * @param name Name of the debug variable
 * @param value Floating point value
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
41
static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
						       uint32_t time_boot_ms, const char *name, float value)
James Goppert's avatar
James Goppert committed
43
{
LM's avatar
LM committed
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
45
	char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN];
LM's avatar
LM committed
46 47 48
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_float(buf, 4, value);
	_mav_put_char_array(buf, 8, name, 10);
Lorenz Meier's avatar
Lorenz Meier committed
49
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
LM's avatar
LM committed
50 51 52 53
#else
	mavlink_named_value_float_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.value = value;
54
	mav_array_memcpy(packet.name, name, sizeof(char)*10);
Lorenz Meier's avatar
Lorenz Meier committed
55
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
LM's avatar
LM committed
56
#endif
James Goppert's avatar
James Goppert committed
57

LM's avatar
LM committed
58
	msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
Lorenz Meier's avatar
Lorenz Meier committed
59 60 61 62 63
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
James Goppert's avatar
James Goppert committed
64 65 66
}

/**
lm's avatar
lm committed
67
 * @brief Pack a named_value_float message on a channel
James Goppert's avatar
James Goppert committed
68 69 70 71
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
72
 * @param time_boot_ms Timestamp (milliseconds since system boot)
James Goppert's avatar
James Goppert committed
73 74 75 76
 * @param name Name of the debug variable
 * @param value Floating point value
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
77 78
static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
79
						           uint32_t time_boot_ms,const char *name,float value)
lm's avatar
lm committed
80
{
LM's avatar
LM committed
81
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
82
	char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN];
LM's avatar
LM committed
83 84 85
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_float(buf, 4, value);
	_mav_put_char_array(buf, 8, name, 10);
Lorenz Meier's avatar
Lorenz Meier committed
86
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
LM's avatar
LM committed
87 88 89 90
#else
	mavlink_named_value_float_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.value = value;
91
	mav_array_memcpy(packet.name, name, sizeof(char)*10);
Lorenz Meier's avatar
Lorenz Meier committed
92
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
LM's avatar
LM committed
93
#endif
lm's avatar
lm committed
94

LM's avatar
LM committed
95
	msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
Lorenz Meier's avatar
Lorenz Meier committed
96 97 98 99 100
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
lm's avatar
lm committed
101 102
}

James Goppert's avatar
James Goppert committed
103 104 105 106 107 108 109 110 111 112
/**
 * @brief Encode a named_value_float struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param named_value_float C-struct to read the message contents from
 */
static inline 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)
{
113
	return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value);
James Goppert's avatar
James Goppert committed
114 115 116 117 118 119
}

/**
 * @brief Send a named_value_float message
 * @param chan MAVLink channel to send the message
 *
120
 * @param time_boot_ms Timestamp (milliseconds since system boot)
James Goppert's avatar
James Goppert committed
121 122 123
 * @param name Name of the debug variable
 * @param value Floating point value
 */
lm's avatar
lm committed
124 125
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

126
static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value)
lm's avatar
lm committed
127
{
LM's avatar
LM committed
128
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
129
	char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN];
LM's avatar
LM committed
130 131 132
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_float(buf, 4, value);
	_mav_put_char_array(buf, 8, name, 10);
Lorenz Meier's avatar
Lorenz Meier committed
133 134 135 136 137
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
LM's avatar
LM committed
138 139 140 141
#else
	mavlink_named_value_float_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.value = value;
142
	mav_array_memcpy(packet.name, name, sizeof(char)*10);
Lorenz Meier's avatar
Lorenz Meier committed
143 144 145 146 147
#if MAVLINK_CRC_EXTRA
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
LM's avatar
LM committed
148
#endif
James Goppert's avatar
James Goppert committed
149 150 151
}

#endif
lm's avatar
lm committed
152

James Goppert's avatar
James Goppert committed
153 154
// MESSAGE NAMED_VALUE_FLOAT UNPACKING

lm's avatar
lm committed
155

156 157 158 159 160 161 162
/**
 * @brief Get field time_boot_ms from named_value_float message
 *
 * @return Timestamp (milliseconds since system boot)
 */
static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg)
{
LM's avatar
LM committed
163
	return _MAV_RETURN_uint32_t(msg,  0);
164 165
}

James Goppert's avatar
James Goppert committed
166 167 168 169 170
/**
 * @brief Get field name from named_value_float message
 *
 * @return Name of the debug variable
 */
lm's avatar
lm committed
171
static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name)
James Goppert's avatar
James Goppert committed
172
{
LM's avatar
LM committed
173
	return _MAV_RETURN_char_array(msg, name, 10,  8);
James Goppert's avatar
James Goppert committed
174 175 176 177 178 179 180 181 182
}

/**
 * @brief Get field value from named_value_float message
 *
 * @return Floating point value
 */
static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
{
LM's avatar
LM committed
183
	return _MAV_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
184 185 186 187 188 189 190 191 192 193
}

/**
 * @brief Decode a named_value_float message into a struct
 *
 * @param msg The message to decode
 * @param named_value_float C-struct to decode the message contents into
 */
static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
{
lm's avatar
lm committed
194
#if MAVLINK_NEED_BYTE_SWAP
195
	named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg);
lm's avatar
lm committed
196 197 198
	named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
	mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
#else
Lorenz Meier's avatar
Lorenz Meier committed
199
	memcpy(named_value_float, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
lm's avatar
lm committed
200
#endif
James Goppert's avatar
James Goppert committed
201
}