Go to the source code of this file.
Classes | |
struct | __mavlink_raw_imu_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_RAW_IMU |
#define | MAVLINK_MSG_ID_27_CRC 144 |
#define | MAVLINK_MSG_ID_27_LEN 26 |
#define | MAVLINK_MSG_ID_RAW_IMU 27 |
#define | MAVLINK_MSG_ID_RAW_IMU_CRC 144 |
#define | MAVLINK_MSG_ID_RAW_IMU_LEN 26 |
Typedefs | |
typedef struct __mavlink_raw_imu_t | mavlink_raw_imu_t |
Functions | |
static void | mavlink_msg_raw_imu_decode (const mavlink_message_t *msg, mavlink_raw_imu_t *raw_imu) |
Decode a raw_imu message into a struct. More... | |
static uint16_t | mavlink_msg_raw_imu_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_raw_imu_t *raw_imu) |
Encode a raw_imu struct. More... | |
static uint16_t | mavlink_msg_raw_imu_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_raw_imu_t *raw_imu) |
Encode a raw_imu struct on a channel. More... | |
static uint64_t | mavlink_msg_raw_imu_get_time_usec (const mavlink_message_t *msg) |
Send a raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_xacc (const mavlink_message_t *msg) |
Get field xacc from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_xgyro (const mavlink_message_t *msg) |
Get field xgyro from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_xmag (const mavlink_message_t *msg) |
Get field xmag from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_yacc (const mavlink_message_t *msg) |
Get field yacc from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_ygyro (const mavlink_message_t *msg) |
Get field ygyro from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_ymag (const mavlink_message_t *msg) |
Get field ymag from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_zacc (const mavlink_message_t *msg) |
Get field zacc from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_zgyro (const mavlink_message_t *msg) |
Get field zgyro from raw_imu message. More... | |
static int16_t | mavlink_msg_raw_imu_get_zmag (const mavlink_message_t *msg) |
Get field zmag from raw_imu message. More... | |
static uint16_t | mavlink_msg_raw_imu_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) |
Pack a raw_imu message. More... | |
static uint16_t | mavlink_msg_raw_imu_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) |
Pack a raw_imu message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_RAW_IMU |
Definition at line 27 of file mavlink_msg_raw_imu.h.
#define MAVLINK_MSG_ID_27_CRC 144 |
Definition at line 23 of file mavlink_msg_raw_imu.h.
#define MAVLINK_MSG_ID_27_LEN 26 |
Definition at line 20 of file mavlink_msg_raw_imu.h.
#define MAVLINK_MSG_ID_RAW_IMU 27 |
Definition at line 3 of file mavlink_msg_raw_imu.h.
#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 |
Definition at line 22 of file mavlink_msg_raw_imu.h.
#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 |
Definition at line 19 of file mavlink_msg_raw_imu.h.
typedef struct __mavlink_raw_imu_t mavlink_raw_imu_t |
|
inlinestatic |
Decode a raw_imu message into a struct.
msg | The message to decode |
raw_imu | C-struct to decode the message contents into |
Definition at line 409 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Encode a raw_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 |
raw_imu | C-struct to read the message contents from |
Definition at line 171 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Encode a raw_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 |
raw_imu | C-struct to read the message contents from |
Definition at line 185 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Send a raw_imu message.
chan | MAVLink channel to send the message |
time_usec | Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
xacc | X acceleration (raw) |
yacc | Y acceleration (raw) |
zacc | Z acceleration (raw) |
xgyro | Angular speed around X axis (raw) |
ygyro | Angular speed around Y axis (raw) |
zgyro | Angular speed around Z axis (raw) |
xmag | X Magnetic field (raw) |
ymag | Y Magnetic field (raw) |
zmag | Z Magnetic field (raw) Get field time_usec from raw_imu message |
Definition at line 308 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field xacc from raw_imu message.
Definition at line 318 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field xgyro from raw_imu message.
Definition at line 348 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field xmag from raw_imu message.
Definition at line 378 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field yacc from raw_imu message.
Definition at line 328 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field ygyro from raw_imu message.
Definition at line 358 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field ymag from raw_imu message.
Definition at line 388 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field zacc from raw_imu message.
Definition at line 338 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field zgyro from raw_imu message.
Definition at line 368 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Get field zmag from raw_imu message.
Definition at line 398 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Pack a raw_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 since UNIX epoch or microseconds since system boot) |
xacc | X acceleration (raw) |
yacc | Y acceleration (raw) |
zacc | Z acceleration (raw) |
xgyro | Angular speed around X axis (raw) |
ygyro | Angular speed around Y axis (raw) |
zgyro | Angular speed around Z axis (raw) |
xmag | X Magnetic field (raw) |
ymag | Y Magnetic field (raw) |
zmag | Z Magnetic field (raw) |
Definition at line 62 of file mavlink_msg_raw_imu.h.
|
inlinestatic |
Pack a raw_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 since UNIX epoch or microseconds since system boot) |
xacc | X acceleration (raw) |
yacc | Y acceleration (raw) |
zacc | Z acceleration (raw) |
xgyro | Angular speed around X axis (raw) |
ygyro | Angular speed around Y axis (raw) |
zgyro | Angular speed around Z axis (raw) |
xmag | X Magnetic field (raw) |
ymag | Y Magnetic field (raw) |
zmag | Z Magnetic field (raw) |
Definition at line 121 of file mavlink_msg_raw_imu.h.