Go to the source code of this file.
Classes | |
struct | __mavlink_scaled_imu2_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_SCALED_IMU2 |
#define | MAVLINK_MSG_ID_116_CRC 76 |
#define | MAVLINK_MSG_ID_116_LEN 22 |
#define | MAVLINK_MSG_ID_SCALED_IMU2 116 |
#define | MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 |
#define | MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 |
Typedefs | |
typedef struct __mavlink_scaled_imu2_t | mavlink_scaled_imu2_t |
Functions | |
static void | mavlink_msg_scaled_imu2_decode (const mavlink_message_t *msg, mavlink_scaled_imu2_t *scaled_imu2) |
Decode a scaled_imu2 message into a struct. | |
static uint16_t | mavlink_msg_scaled_imu2_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_scaled_imu2_t *scaled_imu2) |
Encode a scaled_imu2 struct. | |
static uint16_t | mavlink_msg_scaled_imu2_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_scaled_imu2_t *scaled_imu2) |
Encode a scaled_imu2 struct on a channel. | |
static uint32_t | mavlink_msg_scaled_imu2_get_time_boot_ms (const mavlink_message_t *msg) |
Send a scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_xacc (const mavlink_message_t *msg) |
Get field xacc from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_xgyro (const mavlink_message_t *msg) |
Get field xgyro from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_xmag (const mavlink_message_t *msg) |
Get field xmag from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_yacc (const mavlink_message_t *msg) |
Get field yacc from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_ygyro (const mavlink_message_t *msg) |
Get field ygyro from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_ymag (const mavlink_message_t *msg) |
Get field ymag from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_zacc (const mavlink_message_t *msg) |
Get field zacc from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_zgyro (const mavlink_message_t *msg) |
Get field zgyro from scaled_imu2 message. | |
static int16_t | mavlink_msg_scaled_imu2_get_zmag (const mavlink_message_t *msg) |
Get field zmag from scaled_imu2 message. | |
static uint16_t | mavlink_msg_scaled_imu2_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, 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 scaled_imu2 message. | |
static uint16_t | mavlink_msg_scaled_imu2_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, 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 scaled_imu2 message on a channel. |
#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 |
{ \ "SCALED_IMU2", \ 10, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ } \ }
Definition at line 27 of file mavlink_msg_scaled_imu2.h.
#define MAVLINK_MSG_ID_116_CRC 76 |
Definition at line 23 of file mavlink_msg_scaled_imu2.h.
#define MAVLINK_MSG_ID_116_LEN 22 |
Definition at line 20 of file mavlink_msg_scaled_imu2.h.
#define MAVLINK_MSG_ID_SCALED_IMU2 116 |
Definition at line 3 of file mavlink_msg_scaled_imu2.h.
#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 |
Definition at line 22 of file mavlink_msg_scaled_imu2.h.
#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 |
Definition at line 19 of file mavlink_msg_scaled_imu2.h.
typedef struct __mavlink_scaled_imu2_t mavlink_scaled_imu2_t |
static void mavlink_msg_scaled_imu2_decode | ( | const mavlink_message_t * | msg, |
mavlink_scaled_imu2_t * | scaled_imu2 | ||
) | [inline, static] |
Decode a scaled_imu2 message into a struct.
msg | The message to decode |
scaled_imu2 | C-struct to decode the message contents into |
Definition at line 409 of file mavlink_msg_scaled_imu2.h.
static uint16_t mavlink_msg_scaled_imu2_encode | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
const mavlink_scaled_imu2_t * | scaled_imu2 | ||
) | [inline, static] |
Encode a scaled_imu2 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 |
scaled_imu2 | C-struct to read the message contents from |
Definition at line 171 of file mavlink_msg_scaled_imu2.h.
static uint16_t mavlink_msg_scaled_imu2_encode_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
const mavlink_scaled_imu2_t * | scaled_imu2 | ||
) | [inline, static] |
Encode a scaled_imu2 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 |
scaled_imu2 | C-struct to read the message contents from |
Definition at line 185 of file mavlink_msg_scaled_imu2.h.
static uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a scaled_imu2 message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp (milliseconds since system boot) |
xacc | X acceleration (mg) |
yacc | Y acceleration (mg) |
zacc | Z acceleration (mg) |
xgyro | Angular speed around X axis (millirad /sec) |
ygyro | Angular speed around Y axis (millirad /sec) |
zgyro | Angular speed around Z axis (millirad /sec) |
xmag | X Magnetic field (milli tesla) |
ymag | Y Magnetic field (milli tesla) |
zmag | Z Magnetic field (milli tesla) Get field time_boot_ms from scaled_imu2 message |
Definition at line 308 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_xacc | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field xacc from scaled_imu2 message.
Definition at line 318 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_xgyro | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field xgyro from scaled_imu2 message.
Definition at line 348 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_xmag | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field xmag from scaled_imu2 message.
Definition at line 378 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_yacc | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field yacc from scaled_imu2 message.
Definition at line 328 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_ygyro | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field ygyro from scaled_imu2 message.
Definition at line 358 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_ymag | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field ymag from scaled_imu2 message.
Definition at line 388 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_zacc | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field zacc from scaled_imu2 message.
Definition at line 338 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_zgyro | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field zgyro from scaled_imu2 message.
Definition at line 368 of file mavlink_msg_scaled_imu2.h.
static int16_t mavlink_msg_scaled_imu2_get_zmag | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field zmag from scaled_imu2 message.
Definition at line 398 of file mavlink_msg_scaled_imu2.h.
static uint16_t mavlink_msg_scaled_imu2_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
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 | ||
) | [inline, static] |
Pack a scaled_imu2 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_boot_ms | Timestamp (milliseconds since system boot) |
xacc | X acceleration (mg) |
yacc | Y acceleration (mg) |
zacc | Z acceleration (mg) |
xgyro | Angular speed around X axis (millirad /sec) |
ygyro | Angular speed around Y axis (millirad /sec) |
zgyro | Angular speed around Z axis (millirad /sec) |
xmag | X Magnetic field (milli tesla) |
ymag | Y Magnetic field (milli tesla) |
zmag | Z Magnetic field (milli tesla) |
Definition at line 62 of file mavlink_msg_scaled_imu2.h.
static uint16_t mavlink_msg_scaled_imu2_pack_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
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 | ||
) | [inline, static] |
Pack a scaled_imu2 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_boot_ms | Timestamp (milliseconds since system boot) |
xacc | X acceleration (mg) |
yacc | Y acceleration (mg) |
zacc | Z acceleration (mg) |
xgyro | Angular speed around X axis (millirad /sec) |
ygyro | Angular speed around Y axis (millirad /sec) |
zgyro | Angular speed around Z axis (millirad /sec) |
xmag | X Magnetic field (milli tesla) |
ymag | Y Magnetic field (milli tesla) |
zmag | Z Magnetic field (milli tesla) |
Definition at line 121 of file mavlink_msg_scaled_imu2.h.