3 #define MAVLINK_MSG_ID_HIL_STATE 90
25 #define MAVLINK_MSG_ID_HIL_STATE_LEN 56
26 #define MAVLINK_MSG_ID_90_LEN 56
28 #define MAVLINK_MSG_ID_HIL_STATE_CRC 183
29 #define MAVLINK_MSG_ID_90_CRC 183
33 #define MAVLINK_MESSAGE_INFO_HIL_STATE { \
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) }, \
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)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
126 #if MAVLINK_CRC_EXTRA
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)
161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
204 #if MAVLINK_CRC_EXTRA
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)
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);
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)
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);
259 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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)
263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
282 #if MAVLINK_CRC_EXTRA
306 #if MAVLINK_CRC_EXTRA
314 #if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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)
324 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
325 char *buf = (
char *)msgbuf;
343 #if MAVLINK_CRC_EXTRA
367 #if MAVLINK_CRC_EXTRA
386 static inline uint64_t mavlink_msg_hil_state_get_time_usec(
const mavlink_message_t* msg)
388 return _MAV_RETURN_uint64_t(msg, 0);
396 static inline float mavlink_msg_hil_state_get_roll(
const mavlink_message_t* msg)
398 return _MAV_RETURN_float(msg, 8);
406 static inline float mavlink_msg_hil_state_get_pitch(
const mavlink_message_t* msg)
408 return _MAV_RETURN_float(msg, 12);
416 static inline float mavlink_msg_hil_state_get_yaw(
const mavlink_message_t* msg)
418 return _MAV_RETURN_float(msg, 16);
426 static inline float mavlink_msg_hil_state_get_rollspeed(
const mavlink_message_t* msg)
428 return _MAV_RETURN_float(msg, 20);
436 static inline float mavlink_msg_hil_state_get_pitchspeed(
const mavlink_message_t* msg)
438 return _MAV_RETURN_float(msg, 24);
446 static inline float mavlink_msg_hil_state_get_yawspeed(
const mavlink_message_t* msg)
448 return _MAV_RETURN_float(msg, 28);
456 static inline int32_t mavlink_msg_hil_state_get_lat(
const mavlink_message_t* msg)
458 return _MAV_RETURN_int32_t(msg, 32);
466 static inline int32_t mavlink_msg_hil_state_get_lon(
const mavlink_message_t* msg)
468 return _MAV_RETURN_int32_t(msg, 36);
476 static inline int32_t mavlink_msg_hil_state_get_alt(
const mavlink_message_t* msg)
478 return _MAV_RETURN_int32_t(msg, 40);
486 static inline int16_t mavlink_msg_hil_state_get_vx(
const mavlink_message_t* msg)
488 return _MAV_RETURN_int16_t(msg, 44);
496 static inline int16_t mavlink_msg_hil_state_get_vy(
const mavlink_message_t* msg)
498 return _MAV_RETURN_int16_t(msg, 46);
506 static inline int16_t mavlink_msg_hil_state_get_vz(
const mavlink_message_t* msg)
508 return _MAV_RETURN_int16_t(msg, 48);
516 static inline int16_t mavlink_msg_hil_state_get_xacc(
const mavlink_message_t* msg)
518 return _MAV_RETURN_int16_t(msg, 50);
526 static inline int16_t mavlink_msg_hil_state_get_yacc(
const mavlink_message_t* msg)
528 return _MAV_RETURN_int16_t(msg, 52);
536 static inline int16_t mavlink_msg_hil_state_get_zacc(
const mavlink_message_t* msg)
538 return _MAV_RETURN_int16_t(msg, 54);
547 static inline void mavlink_msg_hil_state_decode(
const mavlink_message_t* msg,
mavlink_hil_state_t* hil_state)
549 #if MAVLINK_NEED_BYTE_SWAP
550 hil_state->
time_usec = mavlink_msg_hil_state_get_time_usec(msg);
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);
554 hil_state->
rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
555 hil_state->
pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
556 hil_state->
yawspeed = mavlink_msg_hil_state_get_yawspeed(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);
int32_t lat
Latitude, expressed as * 1E7.
Definition: mavlink_msg_hil_state.h:14
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
int16_t vx
Ground X Speed (Latitude), expressed as m/s * 100.
Definition: mavlink_msg_hil_state.h:17
float roll
Roll angle (rad)
Definition: mavlink_msg_hil_state.h:8
float yawspeed
Body frame yaw / psi angular speed (rad/s)
Definition: mavlink_msg_hil_state.h:13
Definition: mavlink_msg_hil_state.h:5
#define MAVLINK_MSG_ID_HIL_STATE
Definition: mavlink_msg_hil_state.h:3
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:143
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
int16_t vy
Ground Y Speed (Longitude), expressed as m/s * 100.
Definition: mavlink_msg_hil_state.h:18
int16_t yacc
Y acceleration (mg)
Definition: mavlink_msg_hil_state.h:21
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_HIL_STATE_LEN
Definition: mavlink_msg_hil_state.h:25
int16_t zacc
Z acceleration (mg)
Definition: mavlink_msg_hil_state.h:22
int16_t xacc
X acceleration (mg)
Definition: mavlink_msg_hil_state.h:20
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint64_t time_usec
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Definition: mavlink_msg_hil_state.h:7
float pitchspeed
Body frame pitch / theta angular speed (rad/s)
Definition: mavlink_msg_hil_state.h:12
float yaw
Yaw angle (rad)
Definition: mavlink_msg_hil_state.h:10
int16_t pitch
Definition: accelerometer.h:52
int16_t yaw
Definition: sensors.h:31
float pitch
Pitch angle (rad)
Definition: mavlink_msg_hil_state.h:9
#define MAVLINK_MSG_ID_HIL_STATE_CRC
Definition: mavlink_msg_hil_state.h:28
int32_t alt
Altitude in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_hil_state.h:16
int32_t lon
Longitude, expressed as * 1E7.
Definition: mavlink_msg_hil_state.h:15
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
float rollspeed
Body frame roll / phi angular speed (rad/s)
Definition: mavlink_msg_hil_state.h:11
struct __mavlink_hil_state_t mavlink_hil_state_t
int16_t roll
Definition: accelerometer.h:51
int16_t vz
Ground Z Speed (Altitude), expressed as m/s * 100.
Definition: mavlink_msg_hil_state.h:19