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) }, \ 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 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 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);
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 388 return _MAV_RETURN_uint64_t(msg, 0);
398 return _MAV_RETURN_float(msg, 8);
408 return _MAV_RETURN_float(msg, 12);
418 return _MAV_RETURN_float(msg, 16);
428 return _MAV_RETURN_float(msg, 20);
438 return _MAV_RETURN_float(msg, 24);
448 return _MAV_RETURN_float(msg, 28);
458 return _MAV_RETURN_int32_t(msg, 32);
468 return _MAV_RETURN_int32_t(msg, 36);
478 return _MAV_RETURN_int32_t(msg, 40);
488 return _MAV_RETURN_int16_t(msg, 44);
498 return _MAV_RETURN_int16_t(msg, 46);
508 return _MAV_RETURN_int16_t(msg, 48);
518 return _MAV_RETURN_int16_t(msg, 50);
528 return _MAV_RETURN_int16_t(msg, 52);
538 return _MAV_RETURN_int16_t(msg, 54);
549 #if MAVLINK_NEED_BYTE_SWAP
#define _mav_put_float(buf, wire_offset, b)
static int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t *msg)
Get field lon from hil_state message.
static uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, 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)
Pack a hil_state message.
static int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t *msg)
Get field xacc from hil_state message.
#define MAVLINK_MSG_ID_HIL_STATE
static int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t *msg)
Get field vy from hil_state message.
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.
static int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t *msg)
Get field yacc from hil_state message.
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_hil_state_get_pitch(const mavlink_message_t *msg)
Get field pitch from hil_state message.
static float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t *msg)
Get field yawspeed from hil_state message.
static uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t *msg)
Send a hil_state message.
#define MAVLINK_MSG_ID_HIL_STATE_LEN
static int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t *msg)
Get field vz from hil_state message.
#define _MAV_PAYLOAD(msg)
static int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t *msg)
Get field vx from hil_state message.
static int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t *msg)
Get field lat from hil_state message.
static float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t *msg)
Get field pitchspeed from hil_state message.
static float mavlink_msg_hil_state_get_yaw(const mavlink_message_t *msg)
Get field yaw from hil_state message.
static float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t *msg)
Get field rollspeed from hil_state message.
static int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t *msg)
Get field zacc from hil_state message.
static void mavlink_msg_hil_state_decode(const mavlink_message_t *msg, mavlink_hil_state_t *hil_state)
Decode a hil_state message into a struct.
static int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t *msg)
Get field alt from hil_state message.
#define MAVLINK_MSG_ID_HIL_STATE_CRC
static 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)
Encode a hil_state struct.
static 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_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)
Pack a hil_state message on a channel.
static 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)
Encode a hil_state struct on a channel.
static float mavlink_msg_hil_state_get_roll(const mavlink_message_t *msg)
Get field roll from hil_state message.
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.
#define _mav_put_int16_t(buf, wire_offset, b)
struct __mavlink_hil_state_t mavlink_hil_state_t