Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE NAMED_VALUE_FLOAT PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252 |
||
4 | |||
5 | typedef struct __mavlink_named_value_float_t |
||
6 | { |
||
7 | char name[10]; ///< Name of the debug variable |
||
8 | float value; ///< Floating point value |
||
9 | } mavlink_named_value_float_t; |
||
10 | |||
11 | #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 14 |
||
12 | #define MAVLINK_MSG_ID_252_LEN 14 |
||
13 | |||
14 | #define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 |
||
15 | |||
16 | #define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ |
||
17 | "NAMED_VALUE_FLOAT", \ |
||
18 | 2, \ |
||
19 | { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_float_t, name) }, \ |
||
20 | { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_named_value_float_t, value) }, \ |
||
21 | } \ |
||
22 | } |
||
23 | |||
24 | |||
25 | /** |
||
26 | * @brief Pack a named_value_float message |
||
27 | * @param system_id ID of this system |
||
28 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
29 | * @param msg The MAVLink message to compress the data into |
||
30 | * |
||
31 | * @param name Name of the debug variable |
||
32 | * @param value Floating point value |
||
33 | * @return length of the message in bytes (excluding serial stream start sign) |
||
34 | */ |
||
35 | static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
36 | const char *name, float value) |
||
37 | { |
||
38 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
39 | char buf[14]; |
||
40 | _mav_put_float(buf, 10, value); |
||
41 | _mav_put_char_array(buf, 0, name, 10); |
||
42 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); |
||
43 | #else |
||
44 | mavlink_named_value_float_t packet; |
||
45 | packet.value = value; |
||
46 | mav_array_memcpy(packet.name, name, sizeof(char)*10); |
||
47 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); |
||
48 | #endif |
||
49 | |||
50 | msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; |
||
51 | return mavlink_finalize_message(msg, system_id, component_id, 14); |
||
52 | } |
||
53 | |||
54 | /** |
||
55 | * @brief Pack a named_value_float message on a channel |
||
56 | * @param system_id ID of this system |
||
57 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
58 | * @param chan The MAVLink channel this message was sent over |
||
59 | * @param msg The MAVLink message to compress the data into |
||
60 | * @param name Name of the debug variable |
||
61 | * @param value Floating point value |
||
62 | * @return length of the message in bytes (excluding serial stream start sign) |
||
63 | */ |
||
64 | static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
65 | mavlink_message_t* msg, |
||
66 | const char *name,float value) |
||
67 | { |
||
68 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
69 | char buf[14]; |
||
70 | _mav_put_float(buf, 10, value); |
||
71 | _mav_put_char_array(buf, 0, name, 10); |
||
72 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); |
||
73 | #else |
||
74 | mavlink_named_value_float_t packet; |
||
75 | packet.value = value; |
||
76 | mav_array_memcpy(packet.name, name, sizeof(char)*10); |
||
77 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); |
||
78 | #endif |
||
79 | |||
80 | msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; |
||
81 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14); |
||
82 | } |
||
83 | |||
84 | /** |
||
85 | * @brief Encode a named_value_float struct into a message |
||
86 | * |
||
87 | * @param system_id ID of this system |
||
88 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
89 | * @param msg The MAVLink message to compress the data into |
||
90 | * @param named_value_float C-struct to read the message contents from |
||
91 | */ |
||
92 | 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) |
||
93 | { |
||
94 | return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value); |
||
95 | } |
||
96 | |||
97 | /** |
||
98 | * @brief Send a named_value_float message |
||
99 | * @param chan MAVLink channel to send the message |
||
100 | * |
||
101 | * @param name Name of the debug variable |
||
102 | * @param value Floating point value |
||
103 | */ |
||
104 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
105 | |||
106 | static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char *name, float value) |
||
107 | { |
||
108 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
109 | char buf[14]; |
||
110 | _mav_put_float(buf, 10, value); |
||
111 | _mav_put_char_array(buf, 0, name, 10); |
||
112 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, 14); |
||
113 | #else |
||
114 | mavlink_named_value_float_t packet; |
||
115 | packet.value = value; |
||
116 | mav_array_memcpy(packet.name, name, sizeof(char)*10); |
||
117 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, 14); |
||
118 | #endif |
||
119 | } |
||
120 | |||
121 | #endif |
||
122 | |||
123 | // MESSAGE NAMED_VALUE_FLOAT UNPACKING |
||
124 | |||
125 | |||
126 | /** |
||
127 | * @brief Get field name from named_value_float message |
||
128 | * |
||
129 | * @return Name of the debug variable |
||
130 | */ |
||
131 | static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) |
||
132 | { |
||
133 | return _MAV_RETURN_char_array(msg, name, 10, 0); |
||
134 | } |
||
135 | |||
136 | /** |
||
137 | * @brief Get field value from named_value_float message |
||
138 | * |
||
139 | * @return Floating point value |
||
140 | */ |
||
141 | static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) |
||
142 | { |
||
143 | return _MAV_RETURN_float(msg, 10); |
||
144 | } |
||
145 | |||
146 | /** |
||
147 | * @brief Decode a named_value_float message into a struct |
||
148 | * |
||
149 | * @param msg The message to decode |
||
150 | * @param named_value_float C-struct to decode the message contents into |
||
151 | */ |
||
152 | static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) |
||
153 | { |
||
154 | #if MAVLINK_NEED_BYTE_SWAP |
||
155 | mavlink_msg_named_value_float_get_name(msg, named_value_float->name); |
||
156 | named_value_float->value = mavlink_msg_named_value_float_get_value(msg); |
||
157 | #else |
||
158 | memcpy(named_value_float, _MAV_PAYLOAD(msg), 14); |
||
159 | #endif |
||
160 | } |