Classes | Macros | Typedefs | Functions
mavlink_msg_highres_imu.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_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...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU
Value:
{ \
"HIGHRES_IMU", \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \
{ "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \
{ "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \
{ "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \
{ "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \
} \
}
float temperature
Definition: ms4525.c:41
#define NULL
Definition: usbd_def.h:50

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 Documentation

Function Documentation

static void mavlink_msg_highres_imu_decode ( const mavlink_message_t *  msg,
mavlink_highres_imu_t highres_imu 
)
inlinestatic

Decode a highres_imu message into a struct.

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

Definition at line 524 of file mavlink_msg_highres_imu.h.

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 
)
inlinestatic

Encode a highres_imu 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
highres_imuC-struct to read the message contents from

Definition at line 211 of file mavlink_msg_highres_imu.h.

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 
)
inlinestatic

Encode a highres_imu 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
highres_imuC-struct to read the message contents from

Definition at line 225 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_abs_pressure ( const mavlink_message_t *  msg)
inlinestatic

Get field abs_pressure from highres_imu message.

Returns
Absolute pressure in millibar

Definition at line 473 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_diff_pressure ( const mavlink_message_t *  msg)
inlinestatic

Get field diff_pressure from highres_imu message.

Returns
Differential pressure in millibar

Definition at line 483 of file mavlink_msg_highres_imu.h.

static uint16_t mavlink_msg_highres_imu_get_fields_updated ( const mavlink_message_t *  msg)
inlinestatic

Get field fields_updated from highres_imu message.

Returns
Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature

Definition at line 513 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_pressure_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field pressure_alt from highres_imu message.

Returns
Altitude calculated from pressure

Definition at line 493 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_temperature ( const mavlink_message_t *  msg)
inlinestatic

Get field temperature from highres_imu message.

Returns
Temperature in degrees celsius

Definition at line 503 of file mavlink_msg_highres_imu.h.

static uint64_t mavlink_msg_highres_imu_get_time_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a highres_imu message.

Parameters
chanMAVLink channel to send the message
time_usecTimestamp (microseconds, synced to UNIX time or since system boot)
xaccX acceleration (m/s^2)
yaccY acceleration (m/s^2)
zaccZ acceleration (m/s^2)
xgyroAngular speed around X axis (rad / sec)
ygyroAngular speed around Y axis (rad / sec)
zgyroAngular speed around Z axis (rad / sec)
xmagX Magnetic field (Gauss)
ymagY Magnetic field (Gauss)
zmagZ Magnetic field (Gauss)
abs_pressureAbsolute pressure in millibar
diff_pressureDifferential pressure in millibar
pressure_altAltitude calculated from pressure
temperatureTemperature in degrees celsius
fields_updatedBitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature Get field time_usec from highres_imu message
Returns
Timestamp (microseconds, synced to UNIX time or since system boot)

Definition at line 373 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_xacc ( const mavlink_message_t *  msg)
inlinestatic

Get field xacc from highres_imu message.

Returns
X acceleration (m/s^2)

Definition at line 383 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_xgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field xgyro from highres_imu message.

Returns
Angular speed around X axis (rad / sec)

Definition at line 413 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_xmag ( const mavlink_message_t *  msg)
inlinestatic

Get field xmag from highres_imu message.

Returns
X Magnetic field (Gauss)

Definition at line 443 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_yacc ( const mavlink_message_t *  msg)
inlinestatic

Get field yacc from highres_imu message.

Returns
Y acceleration (m/s^2)

Definition at line 393 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_ygyro ( const mavlink_message_t *  msg)
inlinestatic

Get field ygyro from highres_imu message.

Returns
Angular speed around Y axis (rad / sec)

Definition at line 423 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_ymag ( const mavlink_message_t *  msg)
inlinestatic

Get field ymag from highres_imu message.

Returns
Y Magnetic field (Gauss)

Definition at line 453 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_zacc ( const mavlink_message_t *  msg)
inlinestatic

Get field zacc from highres_imu message.

Returns
Z acceleration (m/s^2)

Definition at line 403 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_zgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field zgyro from highres_imu message.

Returns
Angular speed around Z axis (rad / sec)

Definition at line 433 of file mavlink_msg_highres_imu.h.

static float mavlink_msg_highres_imu_get_zmag ( const mavlink_message_t *  msg)
inlinestatic

Get field zmag from highres_imu message.

Returns
Z Magnetic field (Gauss)

Definition at line 463 of file mavlink_msg_highres_imu.h.

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 
)
inlinestatic

Pack a highres_imu 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_usecTimestamp (microseconds, synced to UNIX time or since system boot)
xaccX acceleration (m/s^2)
yaccY acceleration (m/s^2)
zaccZ acceleration (m/s^2)
xgyroAngular speed around X axis (rad / sec)
ygyroAngular speed around Y axis (rad / sec)
zgyroAngular speed around Z axis (rad / sec)
xmagX Magnetic field (Gauss)
ymagY Magnetic field (Gauss)
zmagZ Magnetic field (Gauss)
abs_pressureAbsolute pressure in millibar
diff_pressureDifferential pressure in millibar
pressure_altAltitude calculated from pressure
temperatureTemperature in degrees celsius
fields_updatedBitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 77 of file mavlink_msg_highres_imu.h.

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 
)
inlinestatic

Pack a highres_imu 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_usecTimestamp (microseconds, synced to UNIX time or since system boot)
xaccX acceleration (m/s^2)
yaccY acceleration (m/s^2)
zaccZ acceleration (m/s^2)
xgyroAngular speed around X axis (rad / sec)
ygyroAngular speed around Y axis (rad / sec)
zgyroAngular speed around Z axis (rad / sec)
xmagX Magnetic field (Gauss)
ymagY Magnetic field (Gauss)
zmagZ Magnetic field (Gauss)
abs_pressureAbsolute pressure in millibar
diff_pressureDifferential pressure in millibar
pressure_altAltitude calculated from pressure
temperatureTemperature in degrees celsius
fields_updatedBitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 151 of file mavlink_msg_highres_imu.h.



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