Classes | Macros | Typedefs | Functions
mavlink_msg_sim_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_sim_state_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SIM_STATE
 
#define MAVLINK_MSG_ID_108_CRC   32
 
#define MAVLINK_MSG_ID_108_LEN   84
 
#define MAVLINK_MSG_ID_SIM_STATE   108
 
#define MAVLINK_MSG_ID_SIM_STATE_CRC   32
 
#define MAVLINK_MSG_ID_SIM_STATE_LEN   84
 

Typedefs

typedef struct __mavlink_sim_state_t mavlink_sim_state_t
 

Functions

static void mavlink_msg_sim_state_decode (const mavlink_message_t *msg, mavlink_sim_state_t *sim_state)
 Decode a sim_state message into a struct. More...
 
static uint16_t mavlink_msg_sim_state_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_sim_state_t *sim_state)
 Encode a sim_state struct. More...
 
static uint16_t mavlink_msg_sim_state_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_sim_state_t *sim_state)
 Encode a sim_state struct on a channel. More...
 
static float mavlink_msg_sim_state_get_alt (const mavlink_message_t *msg)
 Get field alt from sim_state message. More...
 
static float mavlink_msg_sim_state_get_lat (const mavlink_message_t *msg)
 Get field lat from sim_state message. More...
 
static float mavlink_msg_sim_state_get_lon (const mavlink_message_t *msg)
 Get field lon from sim_state message. More...
 
static float mavlink_msg_sim_state_get_pitch (const mavlink_message_t *msg)
 Get field pitch from sim_state message. More...
 
static float mavlink_msg_sim_state_get_q1 (const mavlink_message_t *msg)
 Send a sim_state message. More...
 
static float mavlink_msg_sim_state_get_q2 (const mavlink_message_t *msg)
 Get field q2 from sim_state message. More...
 
static float mavlink_msg_sim_state_get_q3 (const mavlink_message_t *msg)
 Get field q3 from sim_state message. More...
 
static float mavlink_msg_sim_state_get_q4 (const mavlink_message_t *msg)
 Get field q4 from sim_state message. More...
 
static float mavlink_msg_sim_state_get_roll (const mavlink_message_t *msg)
 Get field roll from sim_state message. More...
 
static float mavlink_msg_sim_state_get_std_dev_horz (const mavlink_message_t *msg)
 Get field std_dev_horz from sim_state message. More...
 
static float mavlink_msg_sim_state_get_std_dev_vert (const mavlink_message_t *msg)
 Get field std_dev_vert from sim_state message. More...
 
static float mavlink_msg_sim_state_get_vd (const mavlink_message_t *msg)
 Get field vd from sim_state message. More...
 
static float mavlink_msg_sim_state_get_ve (const mavlink_message_t *msg)
 Get field ve from sim_state message. More...
 
static float mavlink_msg_sim_state_get_vn (const mavlink_message_t *msg)
 Get field vn from sim_state message. More...
 
static float mavlink_msg_sim_state_get_xacc (const mavlink_message_t *msg)
 Get field xacc from sim_state message. More...
 
static float mavlink_msg_sim_state_get_xgyro (const mavlink_message_t *msg)
 Get field xgyro from sim_state message. More...
 
static float mavlink_msg_sim_state_get_yacc (const mavlink_message_t *msg)
 Get field yacc from sim_state message. More...
 
static float mavlink_msg_sim_state_get_yaw (const mavlink_message_t *msg)
 Get field yaw from sim_state message. More...
 
static float mavlink_msg_sim_state_get_ygyro (const mavlink_message_t *msg)
 Get field ygyro from sim_state message. More...
 
static float mavlink_msg_sim_state_get_zacc (const mavlink_message_t *msg)
 Get field zacc from sim_state message. More...
 
static float mavlink_msg_sim_state_get_zgyro (const mavlink_message_t *msg)
 Get field zgyro from sim_state message. More...
 
static uint16_t mavlink_msg_sim_state_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
 Pack a sim_state message. More...
 
static uint16_t mavlink_msg_sim_state_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
 Pack a sim_state message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SIM_STATE
Value:
{ \
"SIM_STATE", \
21, \
{ { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \
{ "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \
{ "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \
{ "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \
{ "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \
{ "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \
{ "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \
{ "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \
{ "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \
} \
}
float alt(float press)
Definition: turbomath.cpp:470
#define NULL
Definition: usbd_def.h:50

Definition at line 38 of file mavlink_msg_sim_state.h.

#define MAVLINK_MSG_ID_108_CRC   32

Definition at line 34 of file mavlink_msg_sim_state.h.

#define MAVLINK_MSG_ID_108_LEN   84

Definition at line 31 of file mavlink_msg_sim_state.h.

#define MAVLINK_MSG_ID_SIM_STATE   108

Definition at line 3 of file mavlink_msg_sim_state.h.

#define MAVLINK_MSG_ID_SIM_STATE_CRC   32

Definition at line 33 of file mavlink_msg_sim_state.h.

#define MAVLINK_MSG_ID_SIM_STATE_LEN   84

Definition at line 30 of file mavlink_msg_sim_state.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_sim_state_decode ( const mavlink_message_t *  msg,
mavlink_sim_state_t sim_state 
)
inlinestatic

Decode a sim_state message into a struct.

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

Definition at line 662 of file mavlink_msg_sim_state.h.

static uint16_t mavlink_msg_sim_state_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_sim_state_t sim_state 
)
inlinestatic

Encode a sim_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
sim_stateC-struct to read the message contents from

Definition at line 259 of file mavlink_msg_sim_state.h.

static uint16_t mavlink_msg_sim_state_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_sim_state_t sim_state 
)
inlinestatic

Encode a sim_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
sim_stateC-struct to read the message contents from

Definition at line 273 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field alt from sim_state message.

Returns
Altitude in meters

Definition at line 601 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from sim_state message.

Returns
Latitude in degrees

Definition at line 581 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from sim_state message.

Returns
Longitude in degrees

Definition at line 591 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_pitch ( const mavlink_message_t *  msg)
inlinestatic

Get field pitch from sim_state message.

Returns
Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs

Definition at line 501 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_q1 ( const mavlink_message_t *  msg)
inlinestatic

Send a sim_state message.

Parameters
chanMAVLink channel to send the message
q1True attitude quaternion component 1, w (1 in null-rotation)
q2True attitude quaternion component 2, x (0 in null-rotation)
q3True attitude quaternion component 3, y (0 in null-rotation)
q4True attitude quaternion component 4, z (0 in null-rotation)
rollAttitude roll expressed as Euler angles, not recommended except for human-readable outputs
pitchAttitude pitch expressed as Euler angles, not recommended except for human-readable outputs
yawAttitude yaw expressed as Euler angles, not recommended except for human-readable outputs
xaccX acceleration m/s/s
yaccY acceleration m/s/s
zaccZ acceleration m/s/s
xgyroAngular speed around X axis rad/s
ygyroAngular speed around Y axis rad/s
zgyroAngular speed around Z axis rad/s
latLatitude in degrees
lonLongitude in degrees
altAltitude in meters
std_dev_horzHorizontal position standard deviation
std_dev_vertVertical position standard deviation
vnTrue velocity in m/s in NORTH direction in earth-fixed NED frame
veTrue velocity in m/s in EAST direction in earth-fixed NED frame
vdTrue velocity in m/s in DOWN direction in earth-fixed NED frame Get field q1 from sim_state message
Returns
True attitude quaternion component 1, w (1 in null-rotation)

Definition at line 451 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_q2 ( const mavlink_message_t *  msg)
inlinestatic

Get field q2 from sim_state message.

Returns
True attitude quaternion component 2, x (0 in null-rotation)

Definition at line 461 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_q3 ( const mavlink_message_t *  msg)
inlinestatic

Get field q3 from sim_state message.

Returns
True attitude quaternion component 3, y (0 in null-rotation)

Definition at line 471 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_q4 ( const mavlink_message_t *  msg)
inlinestatic

Get field q4 from sim_state message.

Returns
True attitude quaternion component 4, z (0 in null-rotation)

Definition at line 481 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_roll ( const mavlink_message_t *  msg)
inlinestatic

Get field roll from sim_state message.

Returns
Attitude roll expressed as Euler angles, not recommended except for human-readable outputs

Definition at line 491 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_std_dev_horz ( const mavlink_message_t *  msg)
inlinestatic

Get field std_dev_horz from sim_state message.

Returns
Horizontal position standard deviation

Definition at line 611 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_std_dev_vert ( const mavlink_message_t *  msg)
inlinestatic

Get field std_dev_vert from sim_state message.

Returns
Vertical position standard deviation

Definition at line 621 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_vd ( const mavlink_message_t *  msg)
inlinestatic

Get field vd from sim_state message.

Returns
True velocity in m/s in DOWN direction in earth-fixed NED frame

Definition at line 651 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_ve ( const mavlink_message_t *  msg)
inlinestatic

Get field ve from sim_state message.

Returns
True velocity in m/s in EAST direction in earth-fixed NED frame

Definition at line 641 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_vn ( const mavlink_message_t *  msg)
inlinestatic

Get field vn from sim_state message.

Returns
True velocity in m/s in NORTH direction in earth-fixed NED frame

Definition at line 631 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_xacc ( const mavlink_message_t *  msg)
inlinestatic

Get field xacc from sim_state message.

Returns
X acceleration m/s/s

Definition at line 521 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_xgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field xgyro from sim_state message.

Returns
Angular speed around X axis rad/s

Definition at line 551 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_yacc ( const mavlink_message_t *  msg)
inlinestatic

Get field yacc from sim_state message.

Returns
Y acceleration m/s/s

Definition at line 531 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from sim_state message.

Returns
Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs

Definition at line 511 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_ygyro ( const mavlink_message_t *  msg)
inlinestatic

Get field ygyro from sim_state message.

Returns
Angular speed around Y axis rad/s

Definition at line 561 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_zacc ( const mavlink_message_t *  msg)
inlinestatic

Get field zacc from sim_state message.

Returns
Z acceleration m/s/s

Definition at line 541 of file mavlink_msg_sim_state.h.

static float mavlink_msg_sim_state_get_zgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field zgyro from sim_state message.

Returns
Angular speed around Z axis rad/s

Definition at line 571 of file mavlink_msg_sim_state.h.

static uint16_t mavlink_msg_sim_state_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
float  q1,
float  q2,
float  q3,
float  q4,
float  roll,
float  pitch,
float  yaw,
float  xacc,
float  yacc,
float  zacc,
float  xgyro,
float  ygyro,
float  zgyro,
float  lat,
float  lon,
float  alt,
float  std_dev_horz,
float  std_dev_vert,
float  vn,
float  ve,
float  vd 
)
inlinestatic

Pack a sim_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
q1True attitude quaternion component 1, w (1 in null-rotation)
q2True attitude quaternion component 2, x (0 in null-rotation)
q3True attitude quaternion component 3, y (0 in null-rotation)
q4True attitude quaternion component 4, z (0 in null-rotation)
rollAttitude roll expressed as Euler angles, not recommended except for human-readable outputs
pitchAttitude pitch expressed as Euler angles, not recommended except for human-readable outputs
yawAttitude yaw expressed as Euler angles, not recommended except for human-readable outputs
xaccX acceleration m/s/s
yaccY acceleration m/s/s
zaccZ acceleration m/s/s
xgyroAngular speed around X axis rad/s
ygyroAngular speed around Y axis rad/s
zgyroAngular speed around Z axis rad/s
latLatitude in degrees
lonLongitude in degrees
altAltitude in meters
std_dev_horzHorizontal position standard deviation
std_dev_vertVertical position standard deviation
vnTrue velocity in m/s in NORTH direction in earth-fixed NED frame
veTrue velocity in m/s in EAST direction in earth-fixed NED frame
vdTrue velocity in m/s in DOWN direction in earth-fixed NED frame
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 95 of file mavlink_msg_sim_state.h.

static uint16_t mavlink_msg_sim_state_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
float  q1,
float  q2,
float  q3,
float  q4,
float  roll,
float  pitch,
float  yaw,
float  xacc,
float  yacc,
float  zacc,
float  xgyro,
float  ygyro,
float  zgyro,
float  lat,
float  lon,
float  alt,
float  std_dev_horz,
float  std_dev_vert,
float  vn,
float  ve,
float  vd 
)
inlinestatic

Pack a sim_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
q1True attitude quaternion component 1, w (1 in null-rotation)
q2True attitude quaternion component 2, x (0 in null-rotation)
q3True attitude quaternion component 3, y (0 in null-rotation)
q4True attitude quaternion component 4, z (0 in null-rotation)
rollAttitude roll expressed as Euler angles, not recommended except for human-readable outputs
pitchAttitude pitch expressed as Euler angles, not recommended except for human-readable outputs
yawAttitude yaw expressed as Euler angles, not recommended except for human-readable outputs
xaccX acceleration m/s/s
yaccY acceleration m/s/s
zaccZ acceleration m/s/s
xgyroAngular speed around X axis rad/s
ygyroAngular speed around Y axis rad/s
zgyroAngular speed around Z axis rad/s
latLatitude in degrees
lonLongitude in degrees
altAltitude in meters
std_dev_horzHorizontal position standard deviation
std_dev_vertVertical position standard deviation
vnTrue velocity in m/s in NORTH direction in earth-fixed NED frame
veTrue velocity in m/s in EAST direction in earth-fixed NED frame
vdTrue velocity in m/s in DOWN direction in earth-fixed NED frame
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 187 of file mavlink_msg_sim_state.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51