Classes | Macros | Typedefs | Functions
mavlink_msg_scaled_imu3.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_scaled_imu3_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SCALED_IMU3
 
#define MAVLINK_MSG_ID_129_CRC   46
 
#define MAVLINK_MSG_ID_129_LEN   22
 
#define MAVLINK_MSG_ID_SCALED_IMU3   129
 
#define MAVLINK_MSG_ID_SCALED_IMU3_CRC   46
 
#define MAVLINK_MSG_ID_SCALED_IMU3_LEN   22
 

Typedefs

typedef struct __mavlink_scaled_imu3_t mavlink_scaled_imu3_t
 

Functions

static void mavlink_msg_scaled_imu3_decode (const mavlink_message_t *msg, mavlink_scaled_imu3_t *scaled_imu3)
 Decode a scaled_imu3 message into a struct. More...
 
static uint16_t mavlink_msg_scaled_imu3_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_scaled_imu3_t *scaled_imu3)
 Encode a scaled_imu3 struct. More...
 
static uint16_t mavlink_msg_scaled_imu3_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_scaled_imu3_t *scaled_imu3)
 Encode a scaled_imu3 struct on a channel. More...
 
static uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms (const mavlink_message_t *msg)
 Send a scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_xacc (const mavlink_message_t *msg)
 Get field xacc from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_xgyro (const mavlink_message_t *msg)
 Get field xgyro from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_xmag (const mavlink_message_t *msg)
 Get field xmag from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_yacc (const mavlink_message_t *msg)
 Get field yacc from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_ygyro (const mavlink_message_t *msg)
 Get field ygyro from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_ymag (const mavlink_message_t *msg)
 Get field ymag from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_zacc (const mavlink_message_t *msg)
 Get field zacc from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_zgyro (const mavlink_message_t *msg)
 Get field zgyro from scaled_imu3 message. More...
 
static int16_t mavlink_msg_scaled_imu3_get_zmag (const mavlink_message_t *msg)
 Get field zmag from scaled_imu3 message. More...
 
static uint16_t mavlink_msg_scaled_imu3_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_imu3 message. More...
 
static uint16_t mavlink_msg_scaled_imu3_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_imu3 message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SCALED_IMU3
Value:
{ \
"SCALED_IMU3", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 27 of file mavlink_msg_scaled_imu3.h.

#define MAVLINK_MSG_ID_129_CRC   46

Definition at line 23 of file mavlink_msg_scaled_imu3.h.

#define MAVLINK_MSG_ID_129_LEN   22

Definition at line 20 of file mavlink_msg_scaled_imu3.h.

#define MAVLINK_MSG_ID_SCALED_IMU3   129

Definition at line 3 of file mavlink_msg_scaled_imu3.h.

#define MAVLINK_MSG_ID_SCALED_IMU3_CRC   46

Definition at line 22 of file mavlink_msg_scaled_imu3.h.

#define MAVLINK_MSG_ID_SCALED_IMU3_LEN   22

Definition at line 19 of file mavlink_msg_scaled_imu3.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_scaled_imu3_decode ( const mavlink_message_t *  msg,
mavlink_scaled_imu3_t scaled_imu3 
)
inlinestatic

Decode a scaled_imu3 message into a struct.

Parameters
msgThe message to decode
scaled_imu3C-struct to decode the message contents into

Definition at line 409 of file mavlink_msg_scaled_imu3.h.

static uint16_t mavlink_msg_scaled_imu3_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_scaled_imu3_t scaled_imu3 
)
inlinestatic

Encode a scaled_imu3 struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
scaled_imu3C-struct to read the message contents from

Definition at line 171 of file mavlink_msg_scaled_imu3.h.

static uint16_t mavlink_msg_scaled_imu3_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_scaled_imu3_t scaled_imu3 
)
inlinestatic

Encode a scaled_imu3 struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
scaled_imu3C-struct to read the message contents from

Definition at line 185 of file mavlink_msg_scaled_imu3.h.

static uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a scaled_imu3 message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
xaccX acceleration (mg)
yaccY acceleration (mg)
zaccZ acceleration (mg)
xgyroAngular speed around X axis (millirad /sec)
ygyroAngular speed around Y axis (millirad /sec)
zgyroAngular speed around Z axis (millirad /sec)
xmagX Magnetic field (milli tesla)
ymagY Magnetic field (milli tesla)
zmagZ Magnetic field (milli tesla) Get field time_boot_ms from scaled_imu3 message
Returns
Timestamp (milliseconds since system boot)

Definition at line 308 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_xacc ( const mavlink_message_t *  msg)
inlinestatic

Get field xacc from scaled_imu3 message.

Returns
X acceleration (mg)

Definition at line 318 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_xgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field xgyro from scaled_imu3 message.

Returns
Angular speed around X axis (millirad /sec)

Definition at line 348 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_xmag ( const mavlink_message_t *  msg)
inlinestatic

Get field xmag from scaled_imu3 message.

Returns
X Magnetic field (milli tesla)

Definition at line 378 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_yacc ( const mavlink_message_t *  msg)
inlinestatic

Get field yacc from scaled_imu3 message.

Returns
Y acceleration (mg)

Definition at line 328 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_ygyro ( const mavlink_message_t *  msg)
inlinestatic

Get field ygyro from scaled_imu3 message.

Returns
Angular speed around Y axis (millirad /sec)

Definition at line 358 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_ymag ( const mavlink_message_t *  msg)
inlinestatic

Get field ymag from scaled_imu3 message.

Returns
Y Magnetic field (milli tesla)

Definition at line 388 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_zacc ( const mavlink_message_t *  msg)
inlinestatic

Get field zacc from scaled_imu3 message.

Returns
Z acceleration (mg)

Definition at line 338 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_zgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field zgyro from scaled_imu3 message.

Returns
Angular speed around Z axis (millirad /sec)

Definition at line 368 of file mavlink_msg_scaled_imu3.h.

static int16_t mavlink_msg_scaled_imu3_get_zmag ( const mavlink_message_t *  msg)
inlinestatic

Get field zmag from scaled_imu3 message.

Returns
Z Magnetic field (milli tesla)

Definition at line 398 of file mavlink_msg_scaled_imu3.h.

static uint16_t mavlink_msg_scaled_imu3_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 
)
inlinestatic

Pack a scaled_imu3 message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
time_boot_msTimestamp (milliseconds since system boot)
xaccX acceleration (mg)
yaccY acceleration (mg)
zaccZ acceleration (mg)
xgyroAngular speed around X axis (millirad /sec)
ygyroAngular speed around Y axis (millirad /sec)
zgyroAngular speed around Z axis (millirad /sec)
xmagX Magnetic field (milli tesla)
ymagY Magnetic field (milli tesla)
zmagZ Magnetic field (milli tesla)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 62 of file mavlink_msg_scaled_imu3.h.

static uint16_t mavlink_msg_scaled_imu3_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 
)
inlinestatic

Pack a scaled_imu3 message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
time_boot_msTimestamp (milliseconds since system boot)
xaccX acceleration (mg)
yaccY acceleration (mg)
zaccZ acceleration (mg)
xgyroAngular speed around X axis (millirad /sec)
ygyroAngular speed around Y axis (millirad /sec)
zgyroAngular speed around Z axis (millirad /sec)
xmagX Magnetic field (milli tesla)
ymagY Magnetic field (milli tesla)
zmagZ Magnetic field (milli tesla)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 121 of file mavlink_msg_scaled_imu3.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51