Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE HIL_STATE PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_HIL_STATE 90 |
||
4 | |||
5 | typedef struct __mavlink_hil_state_t |
||
6 | { |
||
7 | uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
||
8 | float roll; ///< Roll angle (rad) |
||
9 | float pitch; ///< Pitch angle (rad) |
||
10 | float yaw; ///< Yaw angle (rad) |
||
11 | float rollspeed; ///< Roll angular speed (rad/s) |
||
12 | float pitchspeed; ///< Pitch angular speed (rad/s) |
||
13 | float yawspeed; ///< Yaw angular speed (rad/s) |
||
14 | int32_t lat; ///< Latitude, expressed as * 1E7 |
||
15 | int32_t lon; ///< Longitude, expressed as * 1E7 |
||
16 | int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) |
||
17 | int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 |
||
18 | int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 |
||
19 | int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 |
||
20 | int16_t xacc; ///< X acceleration (mg) |
||
21 | int16_t yacc; ///< Y acceleration (mg) |
||
22 | int16_t zacc; ///< Z acceleration (mg) |
||
23 | } mavlink_hil_state_t; |
||
24 | |||
25 | #define MAVLINK_MSG_ID_HIL_STATE_LEN 56 |
||
26 | #define MAVLINK_MSG_ID_90_LEN 56 |
||
27 | |||
28 | |||
29 | |||
30 | #define MAVLINK_MESSAGE_INFO_HIL_STATE { \ |
||
31 | "HIL_STATE", \ |
||
32 | 16, \ |
||
33 | { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ |
||
34 | { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ |
||
35 | { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ |
||
36 | { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ |
||
37 | { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ |
||
38 | { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ |
||
39 | { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ |
||
40 | { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ |
||
41 | { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ |
||
42 | { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ |
||
43 | { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ |
||
44 | { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ |
||
45 | { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ |
||
46 | { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ |
||
47 | { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ |
||
48 | { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ |
||
49 | } \ |
||
50 | } |
||
51 | |||
52 | |||
53 | /** |
||
54 | * @brief Pack a hil_state message |
||
55 | * @param system_id ID of this system |
||
56 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
57 | * @param msg The MAVLink message to compress the data into |
||
58 | * |
||
59 | * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
||
60 | * @param roll Roll angle (rad) |
||
61 | * @param pitch Pitch angle (rad) |
||
62 | * @param yaw Yaw angle (rad) |
||
63 | * @param rollspeed Roll angular speed (rad/s) |
||
64 | * @param pitchspeed Pitch angular speed (rad/s) |
||
65 | * @param yawspeed Yaw angular speed (rad/s) |
||
66 | * @param lat Latitude, expressed as * 1E7 |
||
67 | * @param lon Longitude, expressed as * 1E7 |
||
68 | * @param alt Altitude in meters, expressed as * 1000 (millimeters) |
||
69 | * @param vx Ground X Speed (Latitude), expressed as m/s * 100 |
||
70 | * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 |
||
71 | * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 |
||
72 | * @param xacc X acceleration (mg) |
||
73 | * @param yacc Y acceleration (mg) |
||
74 | * @param zacc Z acceleration (mg) |
||
75 | * @return length of the message in bytes (excluding serial stream start sign) |
||
76 | */ |
||
77 | static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
78 | uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) |
||
79 | { |
||
80 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
81 | char buf[56]; |
||
82 | _mav_put_uint64_t(buf, 0, time_usec); |
||
83 | _mav_put_float(buf, 8, roll); |
||
84 | _mav_put_float(buf, 12, pitch); |
||
85 | _mav_put_float(buf, 16, yaw); |
||
86 | _mav_put_float(buf, 20, rollspeed); |
||
87 | _mav_put_float(buf, 24, pitchspeed); |
||
88 | _mav_put_float(buf, 28, yawspeed); |
||
89 | _mav_put_int32_t(buf, 32, lat); |
||
90 | _mav_put_int32_t(buf, 36, lon); |
||
91 | _mav_put_int32_t(buf, 40, alt); |
||
92 | _mav_put_int16_t(buf, 44, vx); |
||
93 | _mav_put_int16_t(buf, 46, vy); |
||
94 | _mav_put_int16_t(buf, 48, vz); |
||
95 | _mav_put_int16_t(buf, 50, xacc); |
||
96 | _mav_put_int16_t(buf, 52, yacc); |
||
97 | _mav_put_int16_t(buf, 54, zacc); |
||
98 | |||
99 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); |
||
100 | #else |
||
101 | mavlink_hil_state_t packet; |
||
102 | packet.time_usec = time_usec; |
||
103 | packet.roll = roll; |
||
104 | packet.pitch = pitch; |
||
105 | packet.yaw = yaw; |
||
106 | packet.rollspeed = rollspeed; |
||
107 | packet.pitchspeed = pitchspeed; |
||
108 | packet.yawspeed = yawspeed; |
||
109 | packet.lat = lat; |
||
110 | packet.lon = lon; |
||
111 | packet.alt = alt; |
||
112 | packet.vx = vx; |
||
113 | packet.vy = vy; |
||
114 | packet.vz = vz; |
||
115 | packet.xacc = xacc; |
||
116 | packet.yacc = yacc; |
||
117 | packet.zacc = zacc; |
||
118 | |||
119 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); |
||
120 | #endif |
||
121 | |||
122 | msg->msgid = MAVLINK_MSG_ID_HIL_STATE; |
||
123 | return mavlink_finalize_message(msg, system_id, component_id, 56, 183); |
||
124 | } |
||
125 | |||
126 | /** |
||
127 | * @brief Pack a hil_state message on a channel |
||
128 | * @param system_id ID of this system |
||
129 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
130 | * @param chan The MAVLink channel this message was sent over |
||
131 | * @param msg The MAVLink message to compress the data into |
||
132 | * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
||
133 | * @param roll Roll angle (rad) |
||
134 | * @param pitch Pitch angle (rad) |
||
135 | * @param yaw Yaw angle (rad) |
||
136 | * @param rollspeed Roll angular speed (rad/s) |
||
137 | * @param pitchspeed Pitch angular speed (rad/s) |
||
138 | * @param yawspeed Yaw angular speed (rad/s) |
||
139 | * @param lat Latitude, expressed as * 1E7 |
||
140 | * @param lon Longitude, expressed as * 1E7 |
||
141 | * @param alt Altitude in meters, expressed as * 1000 (millimeters) |
||
142 | * @param vx Ground X Speed (Latitude), expressed as m/s * 100 |
||
143 | * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 |
||
144 | * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 |
||
145 | * @param xacc X acceleration (mg) |
||
146 | * @param yacc Y acceleration (mg) |
||
147 | * @param zacc Z acceleration (mg) |
||
148 | * @return length of the message in bytes (excluding serial stream start sign) |
||
149 | */ |
||
150 | static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
151 | mavlink_message_t* msg, |
||
152 | uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) |
||
153 | { |
||
154 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
155 | char buf[56]; |
||
156 | _mav_put_uint64_t(buf, 0, time_usec); |
||
157 | _mav_put_float(buf, 8, roll); |
||
158 | _mav_put_float(buf, 12, pitch); |
||
159 | _mav_put_float(buf, 16, yaw); |
||
160 | _mav_put_float(buf, 20, rollspeed); |
||
161 | _mav_put_float(buf, 24, pitchspeed); |
||
162 | _mav_put_float(buf, 28, yawspeed); |
||
163 | _mav_put_int32_t(buf, 32, lat); |
||
164 | _mav_put_int32_t(buf, 36, lon); |
||
165 | _mav_put_int32_t(buf, 40, alt); |
||
166 | _mav_put_int16_t(buf, 44, vx); |
||
167 | _mav_put_int16_t(buf, 46, vy); |
||
168 | _mav_put_int16_t(buf, 48, vz); |
||
169 | _mav_put_int16_t(buf, 50, xacc); |
||
170 | _mav_put_int16_t(buf, 52, yacc); |
||
171 | _mav_put_int16_t(buf, 54, zacc); |
||
172 | |||
173 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); |
||
174 | #else |
||
175 | mavlink_hil_state_t packet; |
||
176 | packet.time_usec = time_usec; |
||
177 | packet.roll = roll; |
||
178 | packet.pitch = pitch; |
||
179 | packet.yaw = yaw; |
||
180 | packet.rollspeed = rollspeed; |
||
181 | packet.pitchspeed = pitchspeed; |
||
182 | packet.yawspeed = yawspeed; |
||
183 | packet.lat = lat; |
||
184 | packet.lon = lon; |
||
185 | packet.alt = alt; |
||
186 | packet.vx = vx; |
||
187 | packet.vy = vy; |
||
188 | packet.vz = vz; |
||
189 | packet.xacc = xacc; |
||
190 | packet.yacc = yacc; |
||
191 | packet.zacc = zacc; |
||
192 | |||
193 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); |
||
194 | #endif |
||
195 | |||
196 | msg->msgid = MAVLINK_MSG_ID_HIL_STATE; |
||
197 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183); |
||
198 | } |
||
199 | |||
200 | /** |
||
201 | * @brief Encode a hil_state struct into a message |
||
202 | * |
||
203 | * @param system_id ID of this system |
||
204 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
205 | * @param msg The MAVLink message to compress the data into |
||
206 | * @param hil_state C-struct to read the message contents from |
||
207 | */ |
||
208 | static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) |
||
209 | { |
||
210 | return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); |
||
211 | } |
||
212 | |||
213 | /** |
||
214 | * @brief Send a hil_state message |
||
215 | * @param chan MAVLink channel to send the message |
||
216 | * |
||
217 | * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
||
218 | * @param roll Roll angle (rad) |
||
219 | * @param pitch Pitch angle (rad) |
||
220 | * @param yaw Yaw angle (rad) |
||
221 | * @param rollspeed Roll angular speed (rad/s) |
||
222 | * @param pitchspeed Pitch angular speed (rad/s) |
||
223 | * @param yawspeed Yaw angular speed (rad/s) |
||
224 | * @param lat Latitude, expressed as * 1E7 |
||
225 | * @param lon Longitude, expressed as * 1E7 |
||
226 | * @param alt Altitude in meters, expressed as * 1000 (millimeters) |
||
227 | * @param vx Ground X Speed (Latitude), expressed as m/s * 100 |
||
228 | * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 |
||
229 | * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 |
||
230 | * @param xacc X acceleration (mg) |
||
231 | * @param yacc Y acceleration (mg) |
||
232 | * @param zacc Z acceleration (mg) |
||
233 | */ |
||
234 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
235 | |||
236 | static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) |
||
237 | { |
||
238 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
239 | char buf[56]; |
||
240 | _mav_put_uint64_t(buf, 0, time_usec); |
||
241 | _mav_put_float(buf, 8, roll); |
||
242 | _mav_put_float(buf, 12, pitch); |
||
243 | _mav_put_float(buf, 16, yaw); |
||
244 | _mav_put_float(buf, 20, rollspeed); |
||
245 | _mav_put_float(buf, 24, pitchspeed); |
||
246 | _mav_put_float(buf, 28, yawspeed); |
||
247 | _mav_put_int32_t(buf, 32, lat); |
||
248 | _mav_put_int32_t(buf, 36, lon); |
||
249 | _mav_put_int32_t(buf, 40, alt); |
||
250 | _mav_put_int16_t(buf, 44, vx); |
||
251 | _mav_put_int16_t(buf, 46, vy); |
||
252 | _mav_put_int16_t(buf, 48, vz); |
||
253 | _mav_put_int16_t(buf, 50, xacc); |
||
254 | _mav_put_int16_t(buf, 52, yacc); |
||
255 | _mav_put_int16_t(buf, 54, zacc); |
||
256 | |||
257 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56, 183); |
||
258 | #else |
||
259 | mavlink_hil_state_t packet; |
||
260 | packet.time_usec = time_usec; |
||
261 | packet.roll = roll; |
||
262 | packet.pitch = pitch; |
||
263 | packet.yaw = yaw; |
||
264 | packet.rollspeed = rollspeed; |
||
265 | packet.pitchspeed = pitchspeed; |
||
266 | packet.yawspeed = yawspeed; |
||
267 | packet.lat = lat; |
||
268 | packet.lon = lon; |
||
269 | packet.alt = alt; |
||
270 | packet.vx = vx; |
||
271 | packet.vy = vy; |
||
272 | packet.vz = vz; |
||
273 | packet.xacc = xacc; |
||
274 | packet.yacc = yacc; |
||
275 | packet.zacc = zacc; |
||
276 | |||
277 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56, 183); |
||
278 | #endif |
||
279 | } |
||
280 | |||
281 | #endif |
||
282 | |||
283 | // MESSAGE HIL_STATE UNPACKING |
||
284 | |||
285 | |||
286 | /** |
||
287 | * @brief Get field time_usec from hil_state message |
||
288 | * |
||
289 | * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
||
290 | */ |
||
291 | static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) |
||
292 | { |
||
293 | return _MAV_RETURN_uint64_t(msg, 0); |
||
294 | } |
||
295 | |||
296 | /** |
||
297 | * @brief Get field roll from hil_state message |
||
298 | * |
||
299 | * @return Roll angle (rad) |
||
300 | */ |
||
301 | static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) |
||
302 | { |
||
303 | return _MAV_RETURN_float(msg, 8); |
||
304 | } |
||
305 | |||
306 | /** |
||
307 | * @brief Get field pitch from hil_state message |
||
308 | * |
||
309 | * @return Pitch angle (rad) |
||
310 | */ |
||
311 | static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) |
||
312 | { |
||
313 | return _MAV_RETURN_float(msg, 12); |
||
314 | } |
||
315 | |||
316 | /** |
||
317 | * @brief Get field yaw from hil_state message |
||
318 | * |
||
319 | * @return Yaw angle (rad) |
||
320 | */ |
||
321 | static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) |
||
322 | { |
||
323 | return _MAV_RETURN_float(msg, 16); |
||
324 | } |
||
325 | |||
326 | /** |
||
327 | * @brief Get field rollspeed from hil_state message |
||
328 | * |
||
329 | * @return Roll angular speed (rad/s) |
||
330 | */ |
||
331 | static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) |
||
332 | { |
||
333 | return _MAV_RETURN_float(msg, 20); |
||
334 | } |
||
335 | |||
336 | /** |
||
337 | * @brief Get field pitchspeed from hil_state message |
||
338 | * |
||
339 | * @return Pitch angular speed (rad/s) |
||
340 | */ |
||
341 | static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) |
||
342 | { |
||
343 | return _MAV_RETURN_float(msg, 24); |
||
344 | } |
||
345 | |||
346 | /** |
||
347 | * @brief Get field yawspeed from hil_state message |
||
348 | * |
||
349 | * @return Yaw angular speed (rad/s) |
||
350 | */ |
||
351 | static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) |
||
352 | { |
||
353 | return _MAV_RETURN_float(msg, 28); |
||
354 | } |
||
355 | |||
356 | /** |
||
357 | * @brief Get field lat from hil_state message |
||
358 | * |
||
359 | * @return Latitude, expressed as * 1E7 |
||
360 | */ |
||
361 | static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) |
||
362 | { |
||
363 | return _MAV_RETURN_int32_t(msg, 32); |
||
364 | } |
||
365 | |||
366 | /** |
||
367 | * @brief Get field lon from hil_state message |
||
368 | * |
||
369 | * @return Longitude, expressed as * 1E7 |
||
370 | */ |
||
371 | static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) |
||
372 | { |
||
373 | return _MAV_RETURN_int32_t(msg, 36); |
||
374 | } |
||
375 | |||
376 | /** |
||
377 | * @brief Get field alt from hil_state message |
||
378 | * |
||
379 | * @return Altitude in meters, expressed as * 1000 (millimeters) |
||
380 | */ |
||
381 | static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) |
||
382 | { |
||
383 | return _MAV_RETURN_int32_t(msg, 40); |
||
384 | } |
||
385 | |||
386 | /** |
||
387 | * @brief Get field vx from hil_state message |
||
388 | * |
||
389 | * @return Ground X Speed (Latitude), expressed as m/s * 100 |
||
390 | */ |
||
391 | static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) |
||
392 | { |
||
393 | return _MAV_RETURN_int16_t(msg, 44); |
||
394 | } |
||
395 | |||
396 | /** |
||
397 | * @brief Get field vy from hil_state message |
||
398 | * |
||
399 | * @return Ground Y Speed (Longitude), expressed as m/s * 100 |
||
400 | */ |
||
401 | static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) |
||
402 | { |
||
403 | return _MAV_RETURN_int16_t(msg, 46); |
||
404 | } |
||
405 | |||
406 | /** |
||
407 | * @brief Get field vz from hil_state message |
||
408 | * |
||
409 | * @return Ground Z Speed (Altitude), expressed as m/s * 100 |
||
410 | */ |
||
411 | static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) |
||
412 | { |
||
413 | return _MAV_RETURN_int16_t(msg, 48); |
||
414 | } |
||
415 | |||
416 | /** |
||
417 | * @brief Get field xacc from hil_state message |
||
418 | * |
||
419 | * @return X acceleration (mg) |
||
420 | */ |
||
421 | static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) |
||
422 | { |
||
423 | return _MAV_RETURN_int16_t(msg, 50); |
||
424 | } |
||
425 | |||
426 | /** |
||
427 | * @brief Get field yacc from hil_state message |
||
428 | * |
||
429 | * @return Y acceleration (mg) |
||
430 | */ |
||
431 | static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) |
||
432 | { |
||
433 | return _MAV_RETURN_int16_t(msg, 52); |
||
434 | } |
||
435 | |||
436 | /** |
||
437 | * @brief Get field zacc from hil_state message |
||
438 | * |
||
439 | * @return Z acceleration (mg) |
||
440 | */ |
||
441 | static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) |
||
442 | { |
||
443 | return _MAV_RETURN_int16_t(msg, 54); |
||
444 | } |
||
445 | |||
446 | /** |
||
447 | * @brief Decode a hil_state message into a struct |
||
448 | * |
||
449 | * @param msg The message to decode |
||
450 | * @param hil_state C-struct to decode the message contents into |
||
451 | */ |
||
452 | static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) |
||
453 | { |
||
454 | #if MAVLINK_NEED_BYTE_SWAP |
||
455 | hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); |
||
456 | hil_state->roll = mavlink_msg_hil_state_get_roll(msg); |
||
457 | hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); |
||
458 | hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); |
||
459 | hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); |
||
460 | hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); |
||
461 | hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); |
||
462 | hil_state->lat = mavlink_msg_hil_state_get_lat(msg); |
||
463 | hil_state->lon = mavlink_msg_hil_state_get_lon(msg); |
||
464 | hil_state->alt = mavlink_msg_hil_state_get_alt(msg); |
||
465 | hil_state->vx = mavlink_msg_hil_state_get_vx(msg); |
||
466 | hil_state->vy = mavlink_msg_hil_state_get_vy(msg); |
||
467 | hil_state->vz = mavlink_msg_hil_state_get_vz(msg); |
||
468 | hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); |
||
469 | hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); |
||
470 | hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); |
||
471 | #else |
||
472 | memcpy(hil_state, _MAV_PAYLOAD(msg), 56); |
||
473 | #endif |
||
474 | } |