
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... | |
| #define MAVLINK_MESSAGE_INFO_SIM_STATE | 
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 struct __mavlink_sim_state_t mavlink_sim_state_t | 
| 
 | inlinestatic | 
Decode a sim_state message into a struct.
| msg | The message to decode | 
| sim_state | C-struct to decode the message contents into | 
Definition at line 662 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Encode a sim_state struct.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| msg | The MAVLink message to compress the data into | 
| sim_state | C-struct to read the message contents from | 
Definition at line 259 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Encode a sim_state struct on a channel.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| chan | The MAVLink channel this message will be sent over | 
| msg | The MAVLink message to compress the data into | 
| sim_state | C-struct to read the message contents from | 
Definition at line 273 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field alt from sim_state message.
Definition at line 601 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field lat from sim_state message.
Definition at line 581 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field lon from sim_state message.
Definition at line 591 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field pitch from sim_state message.
Definition at line 501 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Send a sim_state message.
| chan | MAVLink channel to send the message | 
| q1 | True attitude quaternion component 1, w (1 in null-rotation) | 
| q2 | True attitude quaternion component 2, x (0 in null-rotation) | 
| q3 | True attitude quaternion component 3, y (0 in null-rotation) | 
| q4 | True attitude quaternion component 4, z (0 in null-rotation) | 
| roll | Attitude roll expressed as Euler angles, not recommended except for human-readable outputs | 
| pitch | Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs | 
| yaw | Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs | 
| xacc | X acceleration m/s/s | 
| yacc | Y acceleration m/s/s | 
| zacc | Z acceleration m/s/s | 
| xgyro | Angular speed around X axis rad/s | 
| ygyro | Angular speed around Y axis rad/s | 
| zgyro | Angular speed around Z axis rad/s | 
| lat | Latitude in degrees | 
| lon | Longitude in degrees | 
| alt | Altitude in meters | 
| std_dev_horz | Horizontal position standard deviation | 
| std_dev_vert | Vertical position standard deviation | 
| vn | True velocity in m/s in NORTH direction in earth-fixed NED frame | 
| ve | True velocity in m/s in EAST direction in earth-fixed NED frame | 
| vd | True velocity in m/s in DOWN direction in earth-fixed NED frame Get field q1 from sim_state message | 
Definition at line 451 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field q2 from sim_state message.
Definition at line 461 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field q3 from sim_state message.
Definition at line 471 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field q4 from sim_state message.
Definition at line 481 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field roll from sim_state message.
Definition at line 491 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field std_dev_horz from sim_state message.
Definition at line 611 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field std_dev_vert from sim_state message.
Definition at line 621 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field vd from sim_state message.
Definition at line 651 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field ve from sim_state message.
Definition at line 641 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field vn from sim_state message.
Definition at line 631 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field xacc from sim_state message.
Definition at line 521 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field xgyro from sim_state message.
Definition at line 551 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field yacc from sim_state message.
Definition at line 531 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field yaw from sim_state message.
Definition at line 511 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field ygyro from sim_state message.
Definition at line 561 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field zacc from sim_state message.
Definition at line 541 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Get field zgyro from sim_state message.
Definition at line 571 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Pack a sim_state message.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| msg | The MAVLink message to compress the data into | 
| q1 | True attitude quaternion component 1, w (1 in null-rotation) | 
| q2 | True attitude quaternion component 2, x (0 in null-rotation) | 
| q3 | True attitude quaternion component 3, y (0 in null-rotation) | 
| q4 | True attitude quaternion component 4, z (0 in null-rotation) | 
| roll | Attitude roll expressed as Euler angles, not recommended except for human-readable outputs | 
| pitch | Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs | 
| yaw | Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs | 
| xacc | X acceleration m/s/s | 
| yacc | Y acceleration m/s/s | 
| zacc | Z acceleration m/s/s | 
| xgyro | Angular speed around X axis rad/s | 
| ygyro | Angular speed around Y axis rad/s | 
| zgyro | Angular speed around Z axis rad/s | 
| lat | Latitude in degrees | 
| lon | Longitude in degrees | 
| alt | Altitude in meters | 
| std_dev_horz | Horizontal position standard deviation | 
| std_dev_vert | Vertical position standard deviation | 
| vn | True velocity in m/s in NORTH direction in earth-fixed NED frame | 
| ve | True velocity in m/s in EAST direction in earth-fixed NED frame | 
| vd | True velocity in m/s in DOWN direction in earth-fixed NED frame | 
Definition at line 95 of file mavlink_msg_sim_state.h.
| 
 | inlinestatic | 
Pack a sim_state message on a channel.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| chan | The MAVLink channel this message will be sent over | 
| msg | The MAVLink message to compress the data into | 
| q1 | True attitude quaternion component 1, w (1 in null-rotation) | 
| q2 | True attitude quaternion component 2, x (0 in null-rotation) | 
| q3 | True attitude quaternion component 3, y (0 in null-rotation) | 
| q4 | True attitude quaternion component 4, z (0 in null-rotation) | 
| roll | Attitude roll expressed as Euler angles, not recommended except for human-readable outputs | 
| pitch | Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs | 
| yaw | Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs | 
| xacc | X acceleration m/s/s | 
| yacc | Y acceleration m/s/s | 
| zacc | Z acceleration m/s/s | 
| xgyro | Angular speed around X axis rad/s | 
| ygyro | Angular speed around Y axis rad/s | 
| zgyro | Angular speed around Z axis rad/s | 
| lat | Latitude in degrees | 
| lon | Longitude in degrees | 
| alt | Altitude in meters | 
| std_dev_horz | Horizontal position standard deviation | 
| std_dev_vert | Vertical position standard deviation | 
| vn | True velocity in m/s in NORTH direction in earth-fixed NED frame | 
| ve | True velocity in m/s in EAST direction in earth-fixed NED frame | 
| vd | True velocity in m/s in DOWN direction in earth-fixed NED frame | 
Definition at line 187 of file mavlink_msg_sim_state.h.