Classes | Macros | Typedefs | Functions
mavlink_msg_hil_state.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_hil_state_t
 

Macros

#define MAVLINK_MESSAGE_INFO_HIL_STATE
 
#define MAVLINK_MSG_ID_90_CRC   183
 
#define MAVLINK_MSG_ID_90_LEN   56
 
#define MAVLINK_MSG_ID_HIL_STATE   90
 
#define MAVLINK_MSG_ID_HIL_STATE_CRC   183
 
#define MAVLINK_MSG_ID_HIL_STATE_LEN   56
 

Typedefs

typedef struct __mavlink_hil_state_t mavlink_hil_state_t
 

Functions

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. More...
 
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. More...
 
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. More...
 
static int32_t mavlink_msg_hil_state_get_alt (const mavlink_message_t *msg)
 Get field alt from hil_state message. More...
 
static int32_t mavlink_msg_hil_state_get_lat (const mavlink_message_t *msg)
 Get field lat from hil_state message. More...
 
static int32_t mavlink_msg_hil_state_get_lon (const mavlink_message_t *msg)
 Get field lon from hil_state message. More...
 
static float mavlink_msg_hil_state_get_pitch (const mavlink_message_t *msg)
 Get field pitch from hil_state message. More...
 
static float mavlink_msg_hil_state_get_pitchspeed (const mavlink_message_t *msg)
 Get field pitchspeed from hil_state message. More...
 
static float mavlink_msg_hil_state_get_roll (const mavlink_message_t *msg)
 Get field roll from hil_state message. More...
 
static float mavlink_msg_hil_state_get_rollspeed (const mavlink_message_t *msg)
 Get field rollspeed from hil_state message. More...
 
static uint64_t mavlink_msg_hil_state_get_time_usec (const mavlink_message_t *msg)
 Send a hil_state message. More...
 
static int16_t mavlink_msg_hil_state_get_vx (const mavlink_message_t *msg)
 Get field vx from hil_state message. More...
 
static int16_t mavlink_msg_hil_state_get_vy (const mavlink_message_t *msg)
 Get field vy from hil_state message. More...
 
static int16_t mavlink_msg_hil_state_get_vz (const mavlink_message_t *msg)
 Get field vz from hil_state message. More...
 
static int16_t mavlink_msg_hil_state_get_xacc (const mavlink_message_t *msg)
 Get field xacc from hil_state message. More...
 
static int16_t mavlink_msg_hil_state_get_yacc (const mavlink_message_t *msg)
 Get field yacc from hil_state message. More...
 
static float mavlink_msg_hil_state_get_yaw (const mavlink_message_t *msg)
 Get field yaw from hil_state message. More...
 
static float mavlink_msg_hil_state_get_yawspeed (const mavlink_message_t *msg)
 Get field yawspeed from hil_state message. More...
 
static int16_t mavlink_msg_hil_state_get_zacc (const mavlink_message_t *msg)
 Get field zacc from hil_state message. More...
 
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. More...
 
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. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_HIL_STATE
Value:
{ \
"HIL_STATE", \
16, \
{ { "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) }, \
} \
}

Definition at line 33 of file mavlink_msg_hil_state.h.

#define MAVLINK_MSG_ID_90_CRC   183

Definition at line 29 of file mavlink_msg_hil_state.h.

#define MAVLINK_MSG_ID_90_LEN   56

Definition at line 26 of file mavlink_msg_hil_state.h.

#define MAVLINK_MSG_ID_HIL_STATE   90

Definition at line 3 of file mavlink_msg_hil_state.h.

#define MAVLINK_MSG_ID_HIL_STATE_CRC   183

Definition at line 28 of file mavlink_msg_hil_state.h.

#define MAVLINK_MSG_ID_HIL_STATE_LEN   56

Definition at line 25 of file mavlink_msg_hil_state.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_hil_state_decode ( const mavlink_message_t *  msg,
mavlink_hil_state_t hil_state 
)
inlinestatic

Decode a hil_state message into a struct.

Parameters
msgThe message to decode
hil_stateC-struct to decode the message contents into

Definition at line 547 of file mavlink_msg_hil_state.h.

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 
)
inlinestatic

Encode a hil_state struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
hil_stateC-struct to read the message contents from

Definition at line 219 of file mavlink_msg_hil_state.h.

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 
)
inlinestatic

Encode a hil_state struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
hil_stateC-struct to read the message contents from

Definition at line 233 of file mavlink_msg_hil_state.h.

static int32_t mavlink_msg_hil_state_get_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field alt from hil_state message.

Returns
Altitude in meters, expressed as * 1000 (millimeters)

Definition at line 476 of file mavlink_msg_hil_state.h.

static int32_t mavlink_msg_hil_state_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from hil_state message.

Returns
Latitude, expressed as * 1E7

Definition at line 456 of file mavlink_msg_hil_state.h.

static int32_t mavlink_msg_hil_state_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from hil_state message.

Returns
Longitude, expressed as * 1E7

Definition at line 466 of file mavlink_msg_hil_state.h.

static float mavlink_msg_hil_state_get_pitch ( const mavlink_message_t *  msg)
inlinestatic

Get field pitch from hil_state message.

Returns
Pitch angle (rad)

Definition at line 406 of file mavlink_msg_hil_state.h.

static float mavlink_msg_hil_state_get_pitchspeed ( const mavlink_message_t *  msg)
inlinestatic

Get field pitchspeed from hil_state message.

Returns
Body frame pitch / theta angular speed (rad/s)

Definition at line 436 of file mavlink_msg_hil_state.h.

static float mavlink_msg_hil_state_get_roll ( const mavlink_message_t *  msg)
inlinestatic

Get field roll from hil_state message.

Returns
Roll angle (rad)

Definition at line 396 of file mavlink_msg_hil_state.h.

static float mavlink_msg_hil_state_get_rollspeed ( const mavlink_message_t *  msg)
inlinestatic

Get field rollspeed from hil_state message.

Returns
Body frame roll / phi angular speed (rad/s)

Definition at line 426 of file mavlink_msg_hil_state.h.

static uint64_t mavlink_msg_hil_state_get_time_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a hil_state message.

Parameters
chanMAVLink channel to send the message
time_usecTimestamp (microseconds since UNIX epoch or microseconds since system boot)
rollRoll angle (rad)
pitchPitch angle (rad)
yawYaw angle (rad)
rollspeedBody frame roll / phi angular speed (rad/s)
pitchspeedBody frame pitch / theta angular speed (rad/s)
yawspeedBody frame yaw / psi angular speed (rad/s)
latLatitude, expressed as * 1E7
lonLongitude, expressed as * 1E7
altAltitude in meters, expressed as * 1000 (millimeters)
vxGround X Speed (Latitude), expressed as m/s * 100
vyGround Y Speed (Longitude), expressed as m/s * 100
vzGround Z Speed (Altitude), expressed as m/s * 100
xaccX acceleration (mg)
yaccY acceleration (mg)
zaccZ acceleration (mg) Get field time_usec from hil_state message
Returns
Timestamp (microseconds since UNIX epoch or microseconds since system boot)

Definition at line 386 of file mavlink_msg_hil_state.h.

static int16_t mavlink_msg_hil_state_get_vx ( const mavlink_message_t *  msg)
inlinestatic

Get field vx from hil_state message.

Returns
Ground X Speed (Latitude), expressed as m/s * 100

Definition at line 486 of file mavlink_msg_hil_state.h.

static int16_t mavlink_msg_hil_state_get_vy ( const mavlink_message_t *  msg)
inlinestatic

Get field vy from hil_state message.

Returns
Ground Y Speed (Longitude), expressed as m/s * 100

Definition at line 496 of file mavlink_msg_hil_state.h.

static int16_t mavlink_msg_hil_state_get_vz ( const mavlink_message_t *  msg)
inlinestatic

Get field vz from hil_state message.

Returns
Ground Z Speed (Altitude), expressed as m/s * 100

Definition at line 506 of file mavlink_msg_hil_state.h.

static int16_t mavlink_msg_hil_state_get_xacc ( const mavlink_message_t *  msg)
inlinestatic

Get field xacc from hil_state message.

Returns
X acceleration (mg)

Definition at line 516 of file mavlink_msg_hil_state.h.

static int16_t mavlink_msg_hil_state_get_yacc ( const mavlink_message_t *  msg)
inlinestatic

Get field yacc from hil_state message.

Returns
Y acceleration (mg)

Definition at line 526 of file mavlink_msg_hil_state.h.

static float mavlink_msg_hil_state_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from hil_state message.

Returns
Yaw angle (rad)

Definition at line 416 of file mavlink_msg_hil_state.h.

static float mavlink_msg_hil_state_get_yawspeed ( const mavlink_message_t *  msg)
inlinestatic

Get field yawspeed from hil_state message.

Returns
Body frame yaw / psi angular speed (rad/s)

Definition at line 446 of file mavlink_msg_hil_state.h.

static int16_t mavlink_msg_hil_state_get_zacc ( const mavlink_message_t *  msg)
inlinestatic

Get field zacc from hil_state message.

Returns
Z acceleration (mg)

Definition at line 536 of file mavlink_msg_hil_state.h.

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 
)
inlinestatic

Pack a hil_state message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
time_usecTimestamp (microseconds since UNIX epoch or microseconds since system boot)
rollRoll angle (rad)
pitchPitch angle (rad)
yawYaw angle (rad)
rollspeedBody frame roll / phi angular speed (rad/s)
pitchspeedBody frame pitch / theta angular speed (rad/s)
yawspeedBody frame yaw / psi angular speed (rad/s)
latLatitude, expressed as * 1E7
lonLongitude, expressed as * 1E7
altAltitude in meters, expressed as * 1000 (millimeters)
vxGround X Speed (Latitude), expressed as m/s * 100
vyGround Y Speed (Longitude), expressed as m/s * 100
vzGround Z Speed (Altitude), expressed as m/s * 100
xaccX acceleration (mg)
yaccY acceleration (mg)
zaccZ acceleration (mg)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 80 of file mavlink_msg_hil_state.h.

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 
)
inlinestatic

Pack a hil_state message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
time_usecTimestamp (microseconds since UNIX epoch or microseconds since system boot)
rollRoll angle (rad)
pitchPitch angle (rad)
yawYaw angle (rad)
rollspeedBody frame roll / phi angular speed (rad/s)
pitchspeedBody frame pitch / theta angular speed (rad/s)
yawspeedBody frame yaw / psi angular speed (rad/s)
latLatitude, expressed as * 1E7
lonLongitude, expressed as * 1E7
altAltitude in meters, expressed as * 1000 (millimeters)
vxGround X Speed (Latitude), expressed as m/s * 100
vyGround Y Speed (Longitude), expressed as m/s * 100
vzGround Z Speed (Altitude), expressed as m/s * 100
xaccX acceleration (mg)
yaccY acceleration (mg)
zaccZ acceleration (mg)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 157 of file mavlink_msg_hil_state.h.



rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:27