
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... | |
| #define MAVLINK_MESSAGE_INFO_HIL_STATE |
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 struct __mavlink_hil_state_t mavlink_hil_state_t |
|
inlinestatic |
Decode a hil_state message into a struct.
| msg | The message to decode |
| hil_state | C-struct to decode the message contents into |
Definition at line 547 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Encode a hil_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 |
| hil_state | C-struct to read the message contents from |
Definition at line 219 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Encode a hil_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 |
| hil_state | C-struct to read the message contents from |
Definition at line 233 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field alt from hil_state message.
Definition at line 476 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field lat from hil_state message.
Definition at line 456 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field lon from hil_state message.
Definition at line 466 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field pitch from hil_state message.
Definition at line 406 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field pitchspeed from hil_state message.
Definition at line 436 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field roll from hil_state message.
Definition at line 396 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field rollspeed from hil_state message.
Definition at line 426 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Send a hil_state message.
| chan | MAVLink channel to send the message |
| time_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
| roll | Roll angle (rad) |
| pitch | Pitch angle (rad) |
| yaw | Yaw angle (rad) |
| rollspeed | Body frame roll / phi angular speed (rad/s) |
| pitchspeed | Body frame pitch / theta angular speed (rad/s) |
| yawspeed | Body frame yaw / psi angular speed (rad/s) |
| lat | Latitude, expressed as * 1E7 |
| lon | Longitude, expressed as * 1E7 |
| alt | Altitude in meters, expressed as * 1000 (millimeters) |
| vx | Ground X Speed (Latitude), expressed as m/s * 100 |
| vy | Ground Y Speed (Longitude), expressed as m/s * 100 |
| vz | Ground Z Speed (Altitude), expressed as m/s * 100 |
| xacc | X acceleration (mg) |
| yacc | Y acceleration (mg) |
| zacc | Z acceleration (mg) Get field time_usec from hil_state message |
Definition at line 386 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field vx from hil_state message.
Definition at line 486 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field vy from hil_state message.
Definition at line 496 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field vz from hil_state message.
Definition at line 506 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field xacc from hil_state message.
Definition at line 516 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field yacc from hil_state message.
Definition at line 526 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field yaw from hil_state message.
Definition at line 416 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field yawspeed from hil_state message.
Definition at line 446 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Get field zacc from hil_state message.
Definition at line 536 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Pack a hil_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 |
| time_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
| roll | Roll angle (rad) |
| pitch | Pitch angle (rad) |
| yaw | Yaw angle (rad) |
| rollspeed | Body frame roll / phi angular speed (rad/s) |
| pitchspeed | Body frame pitch / theta angular speed (rad/s) |
| yawspeed | Body frame yaw / psi angular speed (rad/s) |
| lat | Latitude, expressed as * 1E7 |
| lon | Longitude, expressed as * 1E7 |
| alt | Altitude in meters, expressed as * 1000 (millimeters) |
| vx | Ground X Speed (Latitude), expressed as m/s * 100 |
| vy | Ground Y Speed (Longitude), expressed as m/s * 100 |
| vz | Ground Z Speed (Altitude), expressed as m/s * 100 |
| xacc | X acceleration (mg) |
| yacc | Y acceleration (mg) |
| zacc | Z acceleration (mg) |
Definition at line 80 of file mavlink_msg_hil_state.h.
|
inlinestatic |
Pack a hil_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 |
| time_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
| roll | Roll angle (rad) |
| pitch | Pitch angle (rad) |
| yaw | Yaw angle (rad) |
| rollspeed | Body frame roll / phi angular speed (rad/s) |
| pitchspeed | Body frame pitch / theta angular speed (rad/s) |
| yawspeed | Body frame yaw / psi angular speed (rad/s) |
| lat | Latitude, expressed as * 1E7 |
| lon | Longitude, expressed as * 1E7 |
| alt | Altitude in meters, expressed as * 1000 (millimeters) |
| vx | Ground X Speed (Latitude), expressed as m/s * 100 |
| vy | Ground Y Speed (Longitude), expressed as m/s * 100 |
| vz | Ground Z Speed (Altitude), expressed as m/s * 100 |
| xacc | X acceleration (mg) |
| yacc | Y acceleration (mg) |
| zacc | Z acceleration (mg) |
Definition at line 157 of file mavlink_msg_hil_state.h.