mavlink_msg_hil_state.h
Go to the documentation of this file.
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; /*< Body frame roll / phi angular speed (rad/s)*/
12  float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/
13  float yawspeed; /*< Body frame yaw / psi 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)*/
24 
25 #define MAVLINK_MSG_ID_HIL_STATE_LEN 56
26 #define MAVLINK_MSG_ID_90_LEN 56
27 
28 #define MAVLINK_MSG_ID_HIL_STATE_CRC 183
29 #define MAVLINK_MSG_ID_90_CRC 183
30 
31 
32 
33 #define MAVLINK_MESSAGE_INFO_HIL_STATE { \
34  "HIL_STATE", \
35  16, \
36  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
37  { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
38  { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
39  { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
40  { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
41  { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
42  { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
43  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
44  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
45  { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
46  { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
47  { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
48  { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
49  { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
50  { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
51  { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
52  } \
53 }
54 
55 
80 static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
81  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)
82 {
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85  _mav_put_uint64_t(buf, 0, time_usec);
86  _mav_put_float(buf, 8, roll);
87  _mav_put_float(buf, 12, pitch);
88  _mav_put_float(buf, 16, yaw);
89  _mav_put_float(buf, 20, rollspeed);
90  _mav_put_float(buf, 24, pitchspeed);
91  _mav_put_float(buf, 28, yawspeed);
92  _mav_put_int32_t(buf, 32, lat);
93  _mav_put_int32_t(buf, 36, lon);
94  _mav_put_int32_t(buf, 40, alt);
95  _mav_put_int16_t(buf, 44, vx);
96  _mav_put_int16_t(buf, 46, vy);
97  _mav_put_int16_t(buf, 48, vz);
98  _mav_put_int16_t(buf, 50, xacc);
99  _mav_put_int16_t(buf, 52, yacc);
100  _mav_put_int16_t(buf, 54, zacc);
101 
103 #else
104  mavlink_hil_state_t packet;
105  packet.time_usec = time_usec;
106  packet.roll = roll;
107  packet.pitch = pitch;
108  packet.yaw = yaw;
109  packet.rollspeed = rollspeed;
110  packet.pitchspeed = pitchspeed;
111  packet.yawspeed = yawspeed;
112  packet.lat = lat;
113  packet.lon = lon;
114  packet.alt = alt;
115  packet.vx = vx;
116  packet.vy = vy;
117  packet.vz = vz;
118  packet.xacc = xacc;
119  packet.yacc = yacc;
120  packet.zacc = zacc;
121 
123 #endif
124 
125  msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
126 #if MAVLINK_CRC_EXTRA
128 #else
129  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN);
130 #endif
131 }
132 
157 static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
158  mavlink_message_t* msg,
159  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)
160 {
161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
163  _mav_put_uint64_t(buf, 0, time_usec);
164  _mav_put_float(buf, 8, roll);
165  _mav_put_float(buf, 12, pitch);
166  _mav_put_float(buf, 16, yaw);
167  _mav_put_float(buf, 20, rollspeed);
168  _mav_put_float(buf, 24, pitchspeed);
169  _mav_put_float(buf, 28, yawspeed);
170  _mav_put_int32_t(buf, 32, lat);
171  _mav_put_int32_t(buf, 36, lon);
172  _mav_put_int32_t(buf, 40, alt);
173  _mav_put_int16_t(buf, 44, vx);
174  _mav_put_int16_t(buf, 46, vy);
175  _mav_put_int16_t(buf, 48, vz);
176  _mav_put_int16_t(buf, 50, xacc);
177  _mav_put_int16_t(buf, 52, yacc);
178  _mav_put_int16_t(buf, 54, zacc);
179 
181 #else
182  mavlink_hil_state_t packet;
183  packet.time_usec = time_usec;
184  packet.roll = roll;
185  packet.pitch = pitch;
186  packet.yaw = yaw;
187  packet.rollspeed = rollspeed;
188  packet.pitchspeed = pitchspeed;
189  packet.yawspeed = yawspeed;
190  packet.lat = lat;
191  packet.lon = lon;
192  packet.alt = alt;
193  packet.vx = vx;
194  packet.vy = vy;
195  packet.vz = vz;
196  packet.xacc = xacc;
197  packet.yacc = yacc;
198  packet.zacc = zacc;
199 
201 #endif
202 
203  msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
204 #if MAVLINK_CRC_EXTRA
206 #else
207  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN);
208 #endif
209 }
210 
219 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)
220 {
221  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);
222 }
223 
233 static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
234 {
235  return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, 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);
236 }
237 
259 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
260 
261 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)
262 {
263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
265  _mav_put_uint64_t(buf, 0, time_usec);
266  _mav_put_float(buf, 8, roll);
267  _mav_put_float(buf, 12, pitch);
268  _mav_put_float(buf, 16, yaw);
269  _mav_put_float(buf, 20, rollspeed);
270  _mav_put_float(buf, 24, pitchspeed);
271  _mav_put_float(buf, 28, yawspeed);
272  _mav_put_int32_t(buf, 32, lat);
273  _mav_put_int32_t(buf, 36, lon);
274  _mav_put_int32_t(buf, 40, alt);
275  _mav_put_int16_t(buf, 44, vx);
276  _mav_put_int16_t(buf, 46, vy);
277  _mav_put_int16_t(buf, 48, vz);
278  _mav_put_int16_t(buf, 50, xacc);
279  _mav_put_int16_t(buf, 52, yacc);
280  _mav_put_int16_t(buf, 54, zacc);
281 
282 #if MAVLINK_CRC_EXTRA
283  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
284 #else
285  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
286 #endif
287 #else
288  mavlink_hil_state_t packet;
289  packet.time_usec = time_usec;
290  packet.roll = roll;
291  packet.pitch = pitch;
292  packet.yaw = yaw;
293  packet.rollspeed = rollspeed;
294  packet.pitchspeed = pitchspeed;
295  packet.yawspeed = yawspeed;
296  packet.lat = lat;
297  packet.lon = lon;
298  packet.alt = alt;
299  packet.vx = vx;
300  packet.vy = vy;
301  packet.vz = vz;
302  packet.xacc = xacc;
303  packet.yacc = yacc;
304  packet.zacc = zacc;
305 
306 #if MAVLINK_CRC_EXTRA
307  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
308 #else
309  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
310 #endif
311 #endif
312 }
313 
314 #if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
315 /*
316  This varient of _send() can be used to save stack space by re-using
317  memory from the receive buffer. The caller provides a
318  mavlink_message_t which is the size of a full mavlink message. This
319  is usually the receive buffer for the channel, and allows a reply to an
320  incoming message with minimum stack space usage.
321  */
322 static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, 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)
323 {
324 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
325  char *buf = (char *)msgbuf;
326  _mav_put_uint64_t(buf, 0, time_usec);
327  _mav_put_float(buf, 8, roll);
328  _mav_put_float(buf, 12, pitch);
329  _mav_put_float(buf, 16, yaw);
330  _mav_put_float(buf, 20, rollspeed);
331  _mav_put_float(buf, 24, pitchspeed);
332  _mav_put_float(buf, 28, yawspeed);
333  _mav_put_int32_t(buf, 32, lat);
334  _mav_put_int32_t(buf, 36, lon);
335  _mav_put_int32_t(buf, 40, alt);
336  _mav_put_int16_t(buf, 44, vx);
337  _mav_put_int16_t(buf, 46, vy);
338  _mav_put_int16_t(buf, 48, vz);
339  _mav_put_int16_t(buf, 50, xacc);
340  _mav_put_int16_t(buf, 52, yacc);
341  _mav_put_int16_t(buf, 54, zacc);
342 
343 #if MAVLINK_CRC_EXTRA
344  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
345 #else
346  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
347 #endif
348 #else
349  mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf;
350  packet->time_usec = time_usec;
351  packet->roll = roll;
352  packet->pitch = pitch;
353  packet->yaw = yaw;
354  packet->rollspeed = rollspeed;
355  packet->pitchspeed = pitchspeed;
356  packet->yawspeed = yawspeed;
357  packet->lat = lat;
358  packet->lon = lon;
359  packet->alt = alt;
360  packet->vx = vx;
361  packet->vy = vy;
362  packet->vz = vz;
363  packet->xacc = xacc;
364  packet->yacc = yacc;
365  packet->zacc = zacc;
366 
367 #if MAVLINK_CRC_EXTRA
368  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
369 #else
370  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
371 #endif
372 #endif
373 }
374 #endif
375 
376 #endif
377 
378 // MESSAGE HIL_STATE UNPACKING
379 
380 
386 static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg)
387 {
388  return _MAV_RETURN_uint64_t(msg, 0);
389 }
390 
396 static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
397 {
398  return _MAV_RETURN_float(msg, 8);
399 }
400 
406 static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
407 {
408  return _MAV_RETURN_float(msg, 12);
409 }
410 
416 static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
417 {
418  return _MAV_RETURN_float(msg, 16);
419 }
420 
426 static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
427 {
428  return _MAV_RETURN_float(msg, 20);
429 }
430 
436 static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
437 {
438  return _MAV_RETURN_float(msg, 24);
439 }
440 
446 static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
447 {
448  return _MAV_RETURN_float(msg, 28);
449 }
450 
456 static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
457 {
458  return _MAV_RETURN_int32_t(msg, 32);
459 }
460 
466 static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
467 {
468  return _MAV_RETURN_int32_t(msg, 36);
469 }
470 
476 static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
477 {
478  return _MAV_RETURN_int32_t(msg, 40);
479 }
480 
486 static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
487 {
488  return _MAV_RETURN_int16_t(msg, 44);
489 }
490 
496 static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
497 {
498  return _MAV_RETURN_int16_t(msg, 46);
499 }
500 
506 static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
507 {
508  return _MAV_RETURN_int16_t(msg, 48);
509 }
510 
516 static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
517 {
518  return _MAV_RETURN_int16_t(msg, 50);
519 }
520 
526 static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
527 {
528  return _MAV_RETURN_int16_t(msg, 52);
529 }
530 
536 static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
537 {
538  return _MAV_RETURN_int16_t(msg, 54);
539 }
540 
547 static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
548 {
549 #if MAVLINK_NEED_BYTE_SWAP
551  hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
552  hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
553  hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
557  hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
558  hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
559  hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
560  hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
561  hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
562  hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
563  hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
564  hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
565  hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
566 #else
567  memcpy(hil_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_LEN);
568 #endif
569 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:146


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47