
Go to the source code of this file.
Classes | |
| struct | __mavlink_hil_sensor_t |
Macros | |
| #define | MAVLINK_MESSAGE_INFO_HIL_SENSOR |
| #define | MAVLINK_MSG_ID_107_CRC 108 |
| #define | MAVLINK_MSG_ID_107_LEN 64 |
| #define | MAVLINK_MSG_ID_HIL_SENSOR 107 |
| #define | MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 |
| #define | MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 |
Typedefs | |
| typedef struct __mavlink_hil_sensor_t | mavlink_hil_sensor_t |
Functions | |
| static void | mavlink_msg_hil_sensor_decode (const mavlink_message_t *msg, mavlink_hil_sensor_t *hil_sensor) |
| Decode a hil_sensor message into a struct. More... | |
| static uint16_t | mavlink_msg_hil_sensor_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_hil_sensor_t *hil_sensor) |
| Encode a hil_sensor struct. More... | |
| static uint16_t | mavlink_msg_hil_sensor_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_hil_sensor_t *hil_sensor) |
| Encode a hil_sensor struct on a channel. More... | |
| static float | mavlink_msg_hil_sensor_get_abs_pressure (const mavlink_message_t *msg) |
| Get field abs_pressure from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_diff_pressure (const mavlink_message_t *msg) |
| Get field diff_pressure from hil_sensor message. More... | |
| static uint32_t | mavlink_msg_hil_sensor_get_fields_updated (const mavlink_message_t *msg) |
| Get field fields_updated from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_pressure_alt (const mavlink_message_t *msg) |
| Get field pressure_alt from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_temperature (const mavlink_message_t *msg) |
| Get field temperature from hil_sensor message. More... | |
| static uint64_t | mavlink_msg_hil_sensor_get_time_usec (const mavlink_message_t *msg) |
| Send a hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_xacc (const mavlink_message_t *msg) |
| Get field xacc from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_xgyro (const mavlink_message_t *msg) |
| Get field xgyro from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_xmag (const mavlink_message_t *msg) |
| Get field xmag from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_yacc (const mavlink_message_t *msg) |
| Get field yacc from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_ygyro (const mavlink_message_t *msg) |
| Get field ygyro from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_ymag (const mavlink_message_t *msg) |
| Get field ymag from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_zacc (const mavlink_message_t *msg) |
| Get field zacc from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_zgyro (const mavlink_message_t *msg) |
| Get field zgyro from hil_sensor message. More... | |
| static float | mavlink_msg_hil_sensor_get_zmag (const mavlink_message_t *msg) |
| Get field zmag from hil_sensor message. More... | |
| static uint16_t | mavlink_msg_hil_sensor_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) |
| Pack a hil_sensor message. More... | |
| static uint16_t | mavlink_msg_hil_sensor_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) |
| Pack a hil_sensor message on a channel. More... | |
| #define MAVLINK_MESSAGE_INFO_HIL_SENSOR |
Definition at line 32 of file mavlink_msg_hil_sensor.h.
| #define MAVLINK_MSG_ID_107_CRC 108 |
Definition at line 28 of file mavlink_msg_hil_sensor.h.
| #define MAVLINK_MSG_ID_107_LEN 64 |
Definition at line 25 of file mavlink_msg_hil_sensor.h.
| #define MAVLINK_MSG_ID_HIL_SENSOR 107 |
Definition at line 3 of file mavlink_msg_hil_sensor.h.
| #define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 |
Definition at line 27 of file mavlink_msg_hil_sensor.h.
| #define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 |
Definition at line 24 of file mavlink_msg_hil_sensor.h.
| typedef struct __mavlink_hil_sensor_t mavlink_hil_sensor_t |
|
inlinestatic |
Decode a hil_sensor message into a struct.
| msg | The message to decode |
| hil_sensor | C-struct to decode the message contents into |
Definition at line 524 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Encode a hil_sensor 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_sensor | C-struct to read the message contents from |
Definition at line 211 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Encode a hil_sensor 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_sensor | C-struct to read the message contents from |
Definition at line 225 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field abs_pressure from hil_sensor message.
Definition at line 473 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field diff_pressure from hil_sensor message.
Definition at line 483 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field fields_updated from hil_sensor message.
Definition at line 513 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field pressure_alt from hil_sensor message.
Definition at line 493 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field temperature from hil_sensor message.
Definition at line 503 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Send a hil_sensor message.
| chan | MAVLink channel to send the message |
| time_usec | Timestamp (microseconds, synced to UNIX time or since system boot) |
| xacc | X acceleration (m/s^2) |
| yacc | Y acceleration (m/s^2) |
| zacc | Z acceleration (m/s^2) |
| xgyro | Angular speed around X axis in body frame (rad / sec) |
| ygyro | Angular speed around Y axis in body frame (rad / sec) |
| zgyro | Angular speed around Z axis in body frame (rad / sec) |
| xmag | X Magnetic field (Gauss) |
| ymag | Y Magnetic field (Gauss) |
| zmag | Z Magnetic field (Gauss) |
| abs_pressure | Absolute pressure in millibar |
| diff_pressure | Differential pressure (airspeed) in millibar |
| pressure_alt | Altitude calculated from pressure |
| temperature | Temperature in degrees celsius |
| fields_updated | Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. Get field time_usec from hil_sensor message |
Definition at line 373 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field xacc from hil_sensor message.
Definition at line 383 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field xgyro from hil_sensor message.
Definition at line 413 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field xmag from hil_sensor message.
Definition at line 443 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field yacc from hil_sensor message.
Definition at line 393 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field ygyro from hil_sensor message.
Definition at line 423 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field ymag from hil_sensor message.
Definition at line 453 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field zacc from hil_sensor message.
Definition at line 403 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field zgyro from hil_sensor message.
Definition at line 433 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Get field zmag from hil_sensor message.
Definition at line 463 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Pack a hil_sensor 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, synced to UNIX time or since system boot) |
| xacc | X acceleration (m/s^2) |
| yacc | Y acceleration (m/s^2) |
| zacc | Z acceleration (m/s^2) |
| xgyro | Angular speed around X axis in body frame (rad / sec) |
| ygyro | Angular speed around Y axis in body frame (rad / sec) |
| zgyro | Angular speed around Z axis in body frame (rad / sec) |
| xmag | X Magnetic field (Gauss) |
| ymag | Y Magnetic field (Gauss) |
| zmag | Z Magnetic field (Gauss) |
| abs_pressure | Absolute pressure in millibar |
| diff_pressure | Differential pressure (airspeed) in millibar |
| pressure_alt | Altitude calculated from pressure |
| temperature | Temperature in degrees celsius |
| fields_updated | Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. |
Definition at line 77 of file mavlink_msg_hil_sensor.h.
|
inlinestatic |
Pack a hil_sensor 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, synced to UNIX time or since system boot) |
| xacc | X acceleration (m/s^2) |
| yacc | Y acceleration (m/s^2) |
| zacc | Z acceleration (m/s^2) |
| xgyro | Angular speed around X axis in body frame (rad / sec) |
| ygyro | Angular speed around Y axis in body frame (rad / sec) |
| zgyro | Angular speed around Z axis in body frame (rad / sec) |
| xmag | X Magnetic field (Gauss) |
| ymag | Y Magnetic field (Gauss) |
| zmag | Z Magnetic field (Gauss) |
| abs_pressure | Absolute pressure in millibar |
| diff_pressure | Differential pressure (airspeed) in millibar |
| pressure_alt | Altitude calculated from pressure |
| temperature | Temperature in degrees celsius |
| fields_updated | Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. |
Definition at line 151 of file mavlink_msg_hil_sensor.h.