mavlink_msg_hil_state.h 17.7 KB
Newer Older
1
// MESSAGE HIL_STATE PACKING
2

3
#define MAVLINK_MSG_ID_HIL_STATE 90
4

lm's avatar
lm committed
5
typedef struct __mavlink_hil_state_t
6
{
lm's avatar
lm committed
7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22
 uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 float roll; ///< Roll angle (rad)
 float pitch; ///< Pitch angle (rad)
 float yaw; ///< Yaw angle (rad)
 float rollspeed; ///< Roll angular speed (rad/s)
 float pitchspeed; ///< Pitch angular speed (rad/s)
 float yawspeed; ///< Yaw angular speed (rad/s)
 int32_t lat; ///< Latitude, expressed as * 1E7
 int32_t lon; ///< Longitude, expressed as * 1E7
 int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
 int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
 int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
 int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
 int16_t xacc; ///< X acceleration (mg)
 int16_t yacc; ///< Y acceleration (mg)
 int16_t zacc; ///< Z acceleration (mg)
23
} mavlink_hil_state_t;
24

lm's avatar
lm committed
25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
#define MAVLINK_MSG_ID_HIL_STATE_LEN 56
#define MAVLINK_MSG_ID_90_LEN 56



#define MAVLINK_MESSAGE_INFO_HIL_STATE { \
	"HIL_STATE", \
	16, \
	{  { "time_us", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_us) }, \
         { "roll", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
         { "pitch", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
         { "yaw", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
         { "rollspeed", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
         { "pitchspeed", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
         { "yawspeed", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
         { "lat", MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
         { "lon", MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
         { "alt", MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
         { "vx", MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
         { "vy", MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
         { "vz", MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
         { "xacc", MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
         { "yacc", MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
         { "zacc", MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
         } \
}


53
/**
54
 * @brief Pack a hil_state message
55 56 57 58
 * @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
 *
59
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76
 * @param roll Roll angle (rad)
 * @param pitch Pitch angle (rad)
 * @param yaw Yaw angle (rad)
 * @param rollspeed Roll angular speed (rad/s)
 * @param pitchspeed Pitch angular speed (rad/s)
 * @param yawspeed Yaw angular speed (rad/s)
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
 * @param xacc X acceleration (mg)
 * @param yacc Y acceleration (mg)
 * @param zacc Z acceleration (mg)
 * @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_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint64_t time_us, 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
	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
81

lm's avatar
lm committed
82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99
	put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 8, roll); // Roll angle (rad)
	put_float_by_index(msg, 12, pitch); // Pitch angle (rad)
	put_float_by_index(msg, 16, yaw); // Yaw angle (rad)
	put_float_by_index(msg, 20, rollspeed); // Roll angular speed (rad/s)
	put_float_by_index(msg, 24, pitchspeed); // Pitch angular speed (rad/s)
	put_float_by_index(msg, 28, yawspeed); // Yaw angular speed (rad/s)
	put_int32_t_by_index(msg, 32, lat); // Latitude, expressed as * 1E7
	put_int32_t_by_index(msg, 36, lon); // Longitude, expressed as * 1E7
	put_int32_t_by_index(msg, 40, alt); // Altitude in meters, expressed as * 1000 (millimeters)
	put_int16_t_by_index(msg, 44, vx); // Ground X Speed (Latitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 46, vy); // Ground Y Speed (Longitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 48, vz); // Ground Z Speed (Altitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 50, xacc); // X acceleration (mg)
	put_int16_t_by_index(msg, 52, yacc); // Y acceleration (mg)
	put_int16_t_by_index(msg, 54, zacc); // Z acceleration (mg)

	return mavlink_finalize_message(msg, system_id, component_id, 56, 12);
100 101 102
}

/**
lm's avatar
lm committed
103
 * @brief Pack a hil_state message on a channel
104 105 106 107
 * @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
108
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125
 * @param roll Roll angle (rad)
 * @param pitch Pitch angle (rad)
 * @param yaw Yaw angle (rad)
 * @param rollspeed Roll angular speed (rad/s)
 * @param pitchspeed Pitch angular speed (rad/s)
 * @param yawspeed Yaw angular speed (rad/s)
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
 * @param xacc X acceleration (mg)
 * @param yacc Y acceleration (mg)
 * @param zacc Z acceleration (mg)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177
static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint64_t time_us,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)
{
	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;

	put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 8, roll); // Roll angle (rad)
	put_float_by_index(msg, 12, pitch); // Pitch angle (rad)
	put_float_by_index(msg, 16, yaw); // Yaw angle (rad)
	put_float_by_index(msg, 20, rollspeed); // Roll angular speed (rad/s)
	put_float_by_index(msg, 24, pitchspeed); // Pitch angular speed (rad/s)
	put_float_by_index(msg, 28, yawspeed); // Yaw angular speed (rad/s)
	put_int32_t_by_index(msg, 32, lat); // Latitude, expressed as * 1E7
	put_int32_t_by_index(msg, 36, lon); // Longitude, expressed as * 1E7
	put_int32_t_by_index(msg, 40, alt); // Altitude in meters, expressed as * 1000 (millimeters)
	put_int16_t_by_index(msg, 44, vx); // Ground X Speed (Latitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 46, vy); // Ground Y Speed (Longitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 48, vz); // Ground Z Speed (Altitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 50, xacc); // X acceleration (mg)
	put_int16_t_by_index(msg, 52, yacc); // Y acceleration (mg)
	put_int16_t_by_index(msg, 54, zacc); // Z acceleration (mg)

	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 12);
}

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

/**
 * @brief Pack a hil_state message on a channel and send
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @param roll Roll angle (rad)
 * @param pitch Pitch angle (rad)
 * @param yaw Yaw angle (rad)
 * @param rollspeed Roll angular speed (rad/s)
 * @param pitchspeed Pitch angular speed (rad/s)
 * @param yawspeed Yaw angular speed (rad/s)
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
 * @param xacc X acceleration (mg)
 * @param yacc Y acceleration (mg)
 * @param zacc Z acceleration (mg)
 */
static inline void mavlink_msg_hil_state_pack_chan_send(mavlink_channel_t chan,
							   mavlink_message_t* msg,
						           uint64_t time_us,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)
178
{
179
	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
180

lm's avatar
lm committed
181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198
	put_uint64_t_by_index(msg, 0, time_us); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	put_float_by_index(msg, 8, roll); // Roll angle (rad)
	put_float_by_index(msg, 12, pitch); // Pitch angle (rad)
	put_float_by_index(msg, 16, yaw); // Yaw angle (rad)
	put_float_by_index(msg, 20, rollspeed); // Roll angular speed (rad/s)
	put_float_by_index(msg, 24, pitchspeed); // Pitch angular speed (rad/s)
	put_float_by_index(msg, 28, yawspeed); // Yaw angular speed (rad/s)
	put_int32_t_by_index(msg, 32, lat); // Latitude, expressed as * 1E7
	put_int32_t_by_index(msg, 36, lon); // Longitude, expressed as * 1E7
	put_int32_t_by_index(msg, 40, alt); // Altitude in meters, expressed as * 1000 (millimeters)
	put_int16_t_by_index(msg, 44, vx); // Ground X Speed (Latitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 46, vy); // Ground Y Speed (Longitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 48, vz); // Ground Z Speed (Altitude), expressed as m/s * 100
	put_int16_t_by_index(msg, 50, xacc); // X acceleration (mg)
	put_int16_t_by_index(msg, 52, yacc); // Y acceleration (mg)
	put_int16_t_by_index(msg, 54, zacc); // Z acceleration (mg)

	mavlink_finalize_message_chan_send(msg, chan, 56, 12);
199
}
lm's avatar
lm committed
200 201
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS

202 203

/**
204
 * @brief Encode a hil_state struct into a message
205 206 207 208
 *
 * @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
209
 * @param hil_state C-struct to read the message contents from
210
 */
211
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)
212
{
213
	return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_us, 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);
214 215 216
}

/**
217
 * @brief Send a hil_state message
218 219
 * @param chan MAVLink channel to send the message
 *
220
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236
 * @param roll Roll angle (rad)
 * @param pitch Pitch angle (rad)
 * @param yaw Yaw angle (rad)
 * @param rollspeed Roll angular speed (rad/s)
 * @param pitchspeed Pitch angular speed (rad/s)
 * @param yawspeed Yaw angular speed (rad/s)
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
 * @param xacc X acceleration (mg)
 * @param yacc Y acceleration (mg)
 * @param zacc Z acceleration (mg)
 */
lm's avatar
lm committed
237 238
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

239
static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_us, 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)
240
{
lm's avatar
lm committed
241 242
	MAVLINK_ALIGNED_MESSAGE(msg, 56);
	mavlink_msg_hil_state_pack_chan_send(chan, msg, time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
243 244 245
}

#endif
lm's avatar
lm committed
246

247
// MESSAGE HIL_STATE UNPACKING
248

lm's avatar
lm committed
249

250
/**
251
 * @brief Get field time_us from hil_state message
252 253 254
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
255
static inline uint64_t mavlink_msg_hil_state_get_time_us(const mavlink_message_t* msg)
256
{
lm's avatar
lm committed
257
	return MAVLINK_MSG_RETURN_uint64_t(msg,  0);
258 259 260
}

/**
261
 * @brief Get field roll from hil_state message
262 263 264
 *
 * @return Roll angle (rad)
 */
265
static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
266
{
lm's avatar
lm committed
267
	return MAVLINK_MSG_RETURN_float(msg,  8);
268 269 270
}

/**
271
 * @brief Get field pitch from hil_state message
272 273 274
 *
 * @return Pitch angle (rad)
 */
275
static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
276
{
lm's avatar
lm committed
277
	return MAVLINK_MSG_RETURN_float(msg,  12);
278 279 280
}

/**
281
 * @brief Get field yaw from hil_state message
282 283 284
 *
 * @return Yaw angle (rad)
 */
285
static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
286
{
lm's avatar
lm committed
287
	return MAVLINK_MSG_RETURN_float(msg,  16);
288 289 290
}

/**
291
 * @brief Get field rollspeed from hil_state message
292 293 294
 *
 * @return Roll angular speed (rad/s)
 */
295
static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
296
{
lm's avatar
lm committed
297
	return MAVLINK_MSG_RETURN_float(msg,  20);
298 299 300
}

/**
301
 * @brief Get field pitchspeed from hil_state message
302 303 304
 *
 * @return Pitch angular speed (rad/s)
 */
305
static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
306
{
lm's avatar
lm committed
307
	return MAVLINK_MSG_RETURN_float(msg,  24);
308 309 310
}

/**
311
 * @brief Get field yawspeed from hil_state message
312 313 314
 *
 * @return Yaw angular speed (rad/s)
 */
315
static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
316
{
lm's avatar
lm committed
317
	return MAVLINK_MSG_RETURN_float(msg,  28);
318 319 320
}

/**
321
 * @brief Get field lat from hil_state message
322 323 324
 *
 * @return Latitude, expressed as * 1E7
 */
325
static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
326
{
lm's avatar
lm committed
327
	return MAVLINK_MSG_RETURN_int32_t(msg,  32);
328 329 330
}

/**
331
 * @brief Get field lon from hil_state message
332 333 334
 *
 * @return Longitude, expressed as * 1E7
 */
335
static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
336
{
lm's avatar
lm committed
337
	return MAVLINK_MSG_RETURN_int32_t(msg,  36);
338 339 340
}

/**
341
 * @brief Get field alt from hil_state message
342 343 344
 *
 * @return Altitude in meters, expressed as * 1000 (millimeters)
 */
345
static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
346
{
lm's avatar
lm committed
347
	return MAVLINK_MSG_RETURN_int32_t(msg,  40);
348 349 350
}

/**
351
 * @brief Get field vx from hil_state message
352 353 354
 *
 * @return Ground X Speed (Latitude), expressed as m/s * 100
 */
355
static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
356
{
lm's avatar
lm committed
357
	return MAVLINK_MSG_RETURN_int16_t(msg,  44);
358 359 360
}

/**
361
 * @brief Get field vy from hil_state message
362 363 364
 *
 * @return Ground Y Speed (Longitude), expressed as m/s * 100
 */
365
static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
366
{
lm's avatar
lm committed
367
	return MAVLINK_MSG_RETURN_int16_t(msg,  46);
368 369 370
}

/**
371
 * @brief Get field vz from hil_state message
372 373 374
 *
 * @return Ground Z Speed (Altitude), expressed as m/s * 100
 */
375
static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
376
{
lm's avatar
lm committed
377
	return MAVLINK_MSG_RETURN_int16_t(msg,  48);
378 379 380
}

/**
381
 * @brief Get field xacc from hil_state message
382 383 384
 *
 * @return X acceleration (mg)
 */
385
static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
386
{
lm's avatar
lm committed
387
	return MAVLINK_MSG_RETURN_int16_t(msg,  50);
388 389 390
}

/**
391
 * @brief Get field yacc from hil_state message
392 393 394
 *
 * @return Y acceleration (mg)
 */
395
static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
396
{
lm's avatar
lm committed
397
	return MAVLINK_MSG_RETURN_int16_t(msg,  52);
398 399 400
}

/**
401
 * @brief Get field zacc from hil_state message
402 403 404
 *
 * @return Z acceleration (mg)
 */
405
static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
406
{
lm's avatar
lm committed
407
	return MAVLINK_MSG_RETURN_int16_t(msg,  54);
408 409 410
}

/**
411
 * @brief Decode a hil_state message into a struct
412 413
 *
 * @param msg The message to decode
414
 * @param hil_state C-struct to decode the message contents into
415
 */
416
static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
417
{
lm's avatar
lm committed
418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437
#if MAVLINK_NEED_BYTE_SWAP
	hil_state->time_us = mavlink_msg_hil_state_get_time_us(msg);
	hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
	hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
	hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
	hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
	hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
	hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
	hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
	hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
	hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
	hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
	hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
	hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
	hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
	hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
	hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
#else
	memcpy(hil_state, MAVLINK_PAYLOAD(msg), 56);
#endif
438
}