Go to the source code of this file.
Classes | |
struct | __mavlink_highres_imu_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_HIGHRES_IMU |
#define | MAVLINK_MSG_ID_105_CRC 93 |
#define | MAVLINK_MSG_ID_105_LEN 62 |
#define | MAVLINK_MSG_ID_HIGHRES_IMU 105 |
#define | MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 |
#define | MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 |
Typedefs | |
typedef struct __mavlink_highres_imu_t | mavlink_highres_imu_t |
Functions | |
static void | mavlink_msg_highres_imu_decode (const mavlink_message_t *msg, mavlink_highres_imu_t *highres_imu) |
Decode a highres_imu message into a struct. More... | |
static uint16_t | mavlink_msg_highres_imu_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_highres_imu_t *highres_imu) |
Encode a highres_imu struct. More... | |
static uint16_t | mavlink_msg_highres_imu_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_highres_imu_t *highres_imu) |
Encode a highres_imu struct on a channel. More... | |
static float | mavlink_msg_highres_imu_get_abs_pressure (const mavlink_message_t *msg) |
Get field abs_pressure from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_diff_pressure (const mavlink_message_t *msg) |
Get field diff_pressure from highres_imu message. More... | |
static uint16_t | mavlink_msg_highres_imu_get_fields_updated (const mavlink_message_t *msg) |
Get field fields_updated from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_pressure_alt (const mavlink_message_t *msg) |
Get field pressure_alt from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_temperature (const mavlink_message_t *msg) |
Get field temperature from highres_imu message. More... | |
static uint64_t | mavlink_msg_highres_imu_get_time_usec (const mavlink_message_t *msg) |
Send a highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_xacc (const mavlink_message_t *msg) |
Get field xacc from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_xgyro (const mavlink_message_t *msg) |
Get field xgyro from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_xmag (const mavlink_message_t *msg) |
Get field xmag from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_yacc (const mavlink_message_t *msg) |
Get field yacc from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_ygyro (const mavlink_message_t *msg) |
Get field ygyro from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_ymag (const mavlink_message_t *msg) |
Get field ymag from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_zacc (const mavlink_message_t *msg) |
Get field zacc from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_zgyro (const mavlink_message_t *msg) |
Get field zgyro from highres_imu message. More... | |
static float | mavlink_msg_highres_imu_get_zmag (const mavlink_message_t *msg) |
Get field zmag from highres_imu message. More... | |
static uint16_t | mavlink_msg_highres_imu_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, uint16_t fields_updated) |
Pack a highres_imu message. More... | |
static uint16_t | mavlink_msg_highres_imu_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, uint16_t fields_updated) |
Pack a highres_imu message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU |
Definition at line 32 of file mavlink_msg_highres_imu.h.
#define MAVLINK_MSG_ID_105_CRC 93 |
Definition at line 28 of file mavlink_msg_highres_imu.h.
#define MAVLINK_MSG_ID_105_LEN 62 |
Definition at line 25 of file mavlink_msg_highres_imu.h.
#define MAVLINK_MSG_ID_HIGHRES_IMU 105 |
Definition at line 3 of file mavlink_msg_highres_imu.h.
#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 |
Definition at line 27 of file mavlink_msg_highres_imu.h.
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 |
Definition at line 24 of file mavlink_msg_highres_imu.h.
typedef struct __mavlink_highres_imu_t mavlink_highres_imu_t |
|
inlinestatic |
Decode a highres_imu message into a struct.
msg | The message to decode |
highres_imu | C-struct to decode the message contents into |
Definition at line 524 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Encode a highres_imu 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 |
highres_imu | C-struct to read the message contents from |
Definition at line 211 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Encode a highres_imu 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 |
highres_imu | C-struct to read the message contents from |
Definition at line 225 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field abs_pressure from highres_imu message.
Definition at line 473 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field diff_pressure from highres_imu message.
Definition at line 483 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field fields_updated from highres_imu message.
Definition at line 513 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field pressure_alt from highres_imu message.
Definition at line 493 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field temperature from highres_imu message.
Definition at line 503 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Send a highres_imu 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 (rad / sec) |
ygyro | Angular speed around Y axis (rad / sec) |
zgyro | Angular speed around Z axis (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 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 Get field time_usec from highres_imu message |
Definition at line 373 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field xacc from highres_imu message.
Definition at line 383 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field xgyro from highres_imu message.
Definition at line 413 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field xmag from highres_imu message.
Definition at line 443 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field yacc from highres_imu message.
Definition at line 393 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field ygyro from highres_imu message.
Definition at line 423 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field ymag from highres_imu message.
Definition at line 453 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field zacc from highres_imu message.
Definition at line 403 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field zgyro from highres_imu message.
Definition at line 433 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Get field zmag from highres_imu message.
Definition at line 463 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Pack a highres_imu 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 (rad / sec) |
ygyro | Angular speed around Y axis (rad / sec) |
zgyro | Angular speed around Z axis (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 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 |
Definition at line 77 of file mavlink_msg_highres_imu.h.
|
inlinestatic |
Pack a highres_imu 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 (rad / sec) |
ygyro | Angular speed around Y axis (rad / sec) |
zgyro | Angular speed around Z axis (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 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 |
Definition at line 151 of file mavlink_msg_highres_imu.h.