mavlink_msg_hil_state.h 15.9 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
{
7
 uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
lm's avatar
lm committed
8 9 10 11 12 13 14 15 16 17 18 19 20 21 22
 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
#define MAVLINK_MSG_ID_HIL_STATE_LEN 56
#define MAVLINK_MSG_ID_90_LEN 56



#define MAVLINK_MESSAGE_INFO_HIL_STATE { \
	"HIL_STATE", \
	16, \
lm's avatar
lm committed
33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48
	{  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
         { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
         { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
         { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
         { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
         { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
         { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
         { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
         { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
         { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
lm's avatar
lm committed
49 50 51 52
         } \
}


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_usec 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
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
{
LM's avatar
LM committed
80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[56];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_float(buf, 8, roll);
	_mav_put_float(buf, 12, pitch);
	_mav_put_float(buf, 16, yaw);
	_mav_put_float(buf, 20, rollspeed);
	_mav_put_float(buf, 24, pitchspeed);
	_mav_put_float(buf, 28, yawspeed);
	_mav_put_int32_t(buf, 32, lat);
	_mav_put_int32_t(buf, 36, lon);
	_mav_put_int32_t(buf, 40, alt);
	_mav_put_int16_t(buf, 44, vx);
	_mav_put_int16_t(buf, 46, vy);
	_mav_put_int16_t(buf, 48, vz);
	_mav_put_int16_t(buf, 50, xacc);
	_mav_put_int16_t(buf, 52, yacc);
	_mav_put_int16_t(buf, 54, zacc);

99
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56);
LM's avatar
LM committed
100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118
#else
	mavlink_hil_state_t packet;
	packet.time_usec = time_usec;
	packet.roll = roll;
	packet.pitch = pitch;
	packet.yaw = yaw;
	packet.rollspeed = rollspeed;
	packet.pitchspeed = pitchspeed;
	packet.yawspeed = yawspeed;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.vx = vx;
	packet.vy = vy;
	packet.vz = vz;
	packet.xacc = xacc;
	packet.yacc = yacc;
	packet.zacc = zacc;

119
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56);
LM's avatar
LM committed
120
#endif
lm's avatar
lm committed
121

LM's avatar
LM committed
122
	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
123
	return mavlink_finalize_message(msg, system_id, component_id, 56, 183);
124 125 126
}

/**
lm's avatar
lm committed
127
 * @brief Pack a hil_state message on a channel
128 129 130 131
 * @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
132
 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149
 * @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
150 151
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,
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)
lm's avatar
lm committed
153
{
LM's avatar
LM committed
154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[56];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_float(buf, 8, roll);
	_mav_put_float(buf, 12, pitch);
	_mav_put_float(buf, 16, yaw);
	_mav_put_float(buf, 20, rollspeed);
	_mav_put_float(buf, 24, pitchspeed);
	_mav_put_float(buf, 28, yawspeed);
	_mav_put_int32_t(buf, 32, lat);
	_mav_put_int32_t(buf, 36, lon);
	_mav_put_int32_t(buf, 40, alt);
	_mav_put_int16_t(buf, 44, vx);
	_mav_put_int16_t(buf, 46, vy);
	_mav_put_int16_t(buf, 48, vz);
	_mav_put_int16_t(buf, 50, xacc);
	_mav_put_int16_t(buf, 52, yacc);
	_mav_put_int16_t(buf, 54, zacc);

173
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56);
LM's avatar
LM committed
174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192
#else
	mavlink_hil_state_t packet;
	packet.time_usec = time_usec;
	packet.roll = roll;
	packet.pitch = pitch;
	packet.yaw = yaw;
	packet.rollspeed = rollspeed;
	packet.pitchspeed = pitchspeed;
	packet.yawspeed = yawspeed;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.vx = vx;
	packet.vy = vy;
	packet.vz = vz;
	packet.xacc = xacc;
	packet.yacc = yacc;
	packet.zacc = zacc;

193
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56);
LM's avatar
LM committed
194
#endif
lm's avatar
lm committed
195

LM's avatar
LM committed
196
	msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
197
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183);
lm's avatar
lm committed
198 199 200
}

/**
LM's avatar
LM committed
201 202 203 204
 * @brief Encode a hil_state struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
lm's avatar
lm committed
205
 * @param msg The MAVLink message to compress the data into
LM's avatar
LM committed
206 207 208 209
 * @param hil_state C-struct to read the message contents from
 */
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)
{
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);
LM's avatar
LM committed
211 212 213 214 215 216
}

/**
 * @brief Send a hil_state message
 * @param chan MAVLink channel to send the message
 *
217
 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
lm's avatar
lm committed
218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233
 * @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
234 235
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

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
{
LM's avatar
LM committed
238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[56];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_float(buf, 8, roll);
	_mav_put_float(buf, 12, pitch);
	_mav_put_float(buf, 16, yaw);
	_mav_put_float(buf, 20, rollspeed);
	_mav_put_float(buf, 24, pitchspeed);
	_mav_put_float(buf, 28, yawspeed);
	_mav_put_int32_t(buf, 32, lat);
	_mav_put_int32_t(buf, 36, lon);
	_mav_put_int32_t(buf, 40, alt);
	_mav_put_int16_t(buf, 44, vx);
	_mav_put_int16_t(buf, 46, vy);
	_mav_put_int16_t(buf, 48, vz);
	_mav_put_int16_t(buf, 50, xacc);
	_mav_put_int16_t(buf, 52, yacc);
	_mav_put_int16_t(buf, 54, zacc);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56, 183);
#else
	mavlink_hil_state_t packet;
	packet.time_usec = time_usec;
	packet.roll = roll;
	packet.pitch = pitch;
	packet.yaw = yaw;
	packet.rollspeed = rollspeed;
	packet.pitchspeed = pitchspeed;
	packet.yawspeed = yawspeed;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.vx = vx;
	packet.vy = vy;
	packet.vz = vz;
	packet.xacc = xacc;
	packet.yacc = yacc;
	packet.zacc = zacc;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56, 183);
#endif
279 280 281
}

#endif
lm's avatar
lm committed
282

283
// MESSAGE HIL_STATE UNPACKING
284

lm's avatar
lm committed
285

286
/**
287
 * @brief Get field time_usec from hil_state message
288 289 290
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
291
static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg)
292
{
LM's avatar
LM committed
293
	return _MAV_RETURN_uint64_t(msg,  0);
294 295 296
}

/**
297
 * @brief Get field roll from hil_state message
298 299 300
 *
 * @return Roll angle (rad)
 */
301
static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
302
{
LM's avatar
LM committed
303
	return _MAV_RETURN_float(msg,  8);
304 305 306
}

/**
307
 * @brief Get field pitch from hil_state message
308 309 310
 *
 * @return Pitch angle (rad)
 */
311
static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
312
{
LM's avatar
LM committed
313
	return _MAV_RETURN_float(msg,  12);
314 315 316
}

/**
317
 * @brief Get field yaw from hil_state message
318 319 320
 *
 * @return Yaw angle (rad)
 */
321
static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
322
{
LM's avatar
LM committed
323
	return _MAV_RETURN_float(msg,  16);
324 325 326
}

/**
327
 * @brief Get field rollspeed from hil_state message
328 329 330
 *
 * @return Roll angular speed (rad/s)
 */
331
static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
332
{
LM's avatar
LM committed
333
	return _MAV_RETURN_float(msg,  20);
334 335 336
}

/**
337
 * @brief Get field pitchspeed from hil_state message
338 339 340
 *
 * @return Pitch angular speed (rad/s)
 */
341
static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
342
{
LM's avatar
LM committed
343
	return _MAV_RETURN_float(msg,  24);
344 345 346
}

/**
347
 * @brief Get field yawspeed from hil_state message
348 349 350
 *
 * @return Yaw angular speed (rad/s)
 */
351
static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
352
{
LM's avatar
LM committed
353
	return _MAV_RETURN_float(msg,  28);
354 355 356
}

/**
357
 * @brief Get field lat from hil_state message
358 359 360
 *
 * @return Latitude, expressed as * 1E7
 */
361
static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
362
{
LM's avatar
LM committed
363
	return _MAV_RETURN_int32_t(msg,  32);
364 365 366
}

/**
367
 * @brief Get field lon from hil_state message
368 369 370
 *
 * @return Longitude, expressed as * 1E7
 */
371
static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
372
{
LM's avatar
LM committed
373
	return _MAV_RETURN_int32_t(msg,  36);
374 375 376
}

/**
377
 * @brief Get field alt from hil_state message
378 379 380
 *
 * @return Altitude in meters, expressed as * 1000 (millimeters)
 */
381
static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
382
{
LM's avatar
LM committed
383
	return _MAV_RETURN_int32_t(msg,  40);
384 385 386
}

/**
387
 * @brief Get field vx from hil_state message
388 389 390
 *
 * @return Ground X Speed (Latitude), expressed as m/s * 100
 */
391
static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
392
{
LM's avatar
LM committed
393
	return _MAV_RETURN_int16_t(msg,  44);
394 395 396
}

/**
397
 * @brief Get field vy from hil_state message
398 399 400
 *
 * @return Ground Y Speed (Longitude), expressed as m/s * 100
 */
401
static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
402
{
LM's avatar
LM committed
403
	return _MAV_RETURN_int16_t(msg,  46);
404 405 406
}

/**
407
 * @brief Get field vz from hil_state message
408 409 410
 *
 * @return Ground Z Speed (Altitude), expressed as m/s * 100
 */
411
static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
412
{
LM's avatar
LM committed
413
	return _MAV_RETURN_int16_t(msg,  48);
414 415 416
}

/**
417
 * @brief Get field xacc from hil_state message
418 419 420
 *
 * @return X acceleration (mg)
 */
421
static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
422
{
LM's avatar
LM committed
423
	return _MAV_RETURN_int16_t(msg,  50);
424 425 426
}

/**
427
 * @brief Get field yacc from hil_state message
428 429 430
 *
 * @return Y acceleration (mg)
 */
431
static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
432
{
LM's avatar
LM committed
433
	return _MAV_RETURN_int16_t(msg,  52);
434 435 436
}

/**
437
 * @brief Get field zacc from hil_state message
438 439 440
 *
 * @return Z acceleration (mg)
 */
441
static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
442
{
LM's avatar
LM committed
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
{
lm's avatar
lm committed
454
#if MAVLINK_NEED_BYTE_SWAP
455
	hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg);
lm's avatar
lm committed
456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471
	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
LM's avatar
LM committed
472
	memcpy(hil_state, _MAV_PAYLOAD(msg), 56);
lm's avatar
lm committed
473
#endif
474
}