Classes | Macros | Typedefs | Functions
mavlink_msg_camera_stamped_small_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_camera_stamped_small_imu_t
 

Macros

#define MAVLINK_MESSAGE_INFO_CAMERA_STAMPED_SMALL_IMU
 
#define MAVLINK_MSG_ID_185_CRC   209
 
#define MAVLINK_MSG_ID_185_LEN   37
 
#define MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU   185
 
#define MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC   209
 
#define MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN   37
 

Typedefs

typedef struct __mavlink_camera_stamped_small_imu_t mavlink_camera_stamped_small_imu_t
 

Functions

static void mavlink_msg_camera_stamped_small_imu_decode (const mavlink_message_t *msg, mavlink_camera_stamped_small_imu_t *camera_stamped_small_imu)
 Decode a camera_stamped_small_imu message into a struct. More...
 
static uint16_t mavlink_msg_camera_stamped_small_imu_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_camera_stamped_small_imu_t *camera_stamped_small_imu)
 Encode a camera_stamped_small_imu struct. More...
 
static uint16_t mavlink_msg_camera_stamped_small_imu_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_camera_stamped_small_imu_t *camera_stamped_small_imu)
 Encode a camera_stamped_small_imu struct on a channel. More...
 
static uint8_t mavlink_msg_camera_stamped_small_imu_get_image (const mavlink_message_t *msg)
 Get field image from camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_temperature (const mavlink_message_t *msg)
 Get field temperature from camera_stamped_small_imu message. More...
 
static uint64_t mavlink_msg_camera_stamped_small_imu_get_time_boot_us (const mavlink_message_t *msg)
 Send a camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_xacc (const mavlink_message_t *msg)
 Get field xacc from camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_xgyro (const mavlink_message_t *msg)
 Get field xgyro from camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_yacc (const mavlink_message_t *msg)
 Get field yacc from camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_ygyro (const mavlink_message_t *msg)
 Get field ygyro from camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_zacc (const mavlink_message_t *msg)
 Get field zacc from camera_stamped_small_imu message. More...
 
static float mavlink_msg_camera_stamped_small_imu_get_zgyro (const mavlink_message_t *msg)
 Get field zgyro from camera_stamped_small_imu message. More...
 
static uint16_t mavlink_msg_camera_stamped_small_imu_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature, uint8_t image)
 Pack a camera_stamped_small_imu message. More...
 
static uint16_t mavlink_msg_camera_stamped_small_imu_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature, uint8_t image)
 Pack a camera_stamped_small_imu message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_CAMERA_STAMPED_SMALL_IMU
Value:
{ \
"CAMERA_STAMPED_SMALL_IMU", \
9, \
{ { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_stamped_small_imu_t, time_boot_us) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_stamped_small_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_stamped_small_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_stamped_small_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_stamped_small_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_stamped_small_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_stamped_small_imu_t, zgyro) }, \
{ "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_stamped_small_imu_t, temperature) }, \
{ "image", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_camera_stamped_small_imu_t, image) }, \
} \
}
float temperature
Definition: ms4525.c:41
#define NULL
Definition: usbd_def.h:50

Definition at line 26 of file mavlink_msg_camera_stamped_small_imu.h.

#define MAVLINK_MSG_ID_185_CRC   209

Definition at line 22 of file mavlink_msg_camera_stamped_small_imu.h.

#define MAVLINK_MSG_ID_185_LEN   37

Definition at line 19 of file mavlink_msg_camera_stamped_small_imu.h.

#define MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU   185

Definition at line 3 of file mavlink_msg_camera_stamped_small_imu.h.

#define MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC   209

Definition at line 21 of file mavlink_msg_camera_stamped_small_imu.h.

#define MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN   37

Definition at line 18 of file mavlink_msg_camera_stamped_small_imu.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_camera_stamped_small_imu_decode ( const mavlink_message_t *  msg,
mavlink_camera_stamped_small_imu_t camera_stamped_small_imu 
)
inlinestatic

Decode a camera_stamped_small_imu message into a struct.

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

Definition at line 386 of file mavlink_msg_camera_stamped_small_imu.h.

static uint16_t mavlink_msg_camera_stamped_small_imu_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_camera_stamped_small_imu_t camera_stamped_small_imu 
)
inlinestatic

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

Definition at line 163 of file mavlink_msg_camera_stamped_small_imu.h.

static uint16_t mavlink_msg_camera_stamped_small_imu_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_camera_stamped_small_imu_t camera_stamped_small_imu 
)
inlinestatic

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

Definition at line 177 of file mavlink_msg_camera_stamped_small_imu.h.

static uint8_t mavlink_msg_camera_stamped_small_imu_get_image ( const mavlink_message_t *  msg)
inlinestatic

Get field image from camera_stamped_small_imu message.

Returns
True if there is an image associated with this measurement

Definition at line 375 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_temperature ( const mavlink_message_t *  msg)
inlinestatic

Get field temperature from camera_stamped_small_imu message.

Returns
Internal temperature measurement

Definition at line 365 of file mavlink_msg_camera_stamped_small_imu.h.

static uint64_t mavlink_msg_camera_stamped_small_imu_get_time_boot_us ( const mavlink_message_t *  msg)
inlinestatic

Send a camera_stamped_small_imu message.

Parameters
chanMAVLink channel to send the message
time_boot_usMeasurement timestamp as microseconds since boot
xaccAcceleration along X axis
yaccAcceleration along Y axis
zaccAcceleration along Z axis
xgyroAngular speed around X axis
ygyroAngular speed around Y axis
zgyroAngular speed around Z axis
temperatureInternal temperature measurement
imageTrue if there is an image associated with this measurement Get field time_boot_us from camera_stamped_small_imu message
Returns
Measurement timestamp as microseconds since boot

Definition at line 295 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_xacc ( const mavlink_message_t *  msg)
inlinestatic

Get field xacc from camera_stamped_small_imu message.

Returns
Acceleration along X axis

Definition at line 305 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_xgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field xgyro from camera_stamped_small_imu message.

Returns
Angular speed around X axis

Definition at line 335 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_yacc ( const mavlink_message_t *  msg)
inlinestatic

Get field yacc from camera_stamped_small_imu message.

Returns
Acceleration along Y axis

Definition at line 315 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_ygyro ( const mavlink_message_t *  msg)
inlinestatic

Get field ygyro from camera_stamped_small_imu message.

Returns
Angular speed around Y axis

Definition at line 345 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_zacc ( const mavlink_message_t *  msg)
inlinestatic

Get field zacc from camera_stamped_small_imu message.

Returns
Acceleration along Z axis

Definition at line 325 of file mavlink_msg_camera_stamped_small_imu.h.

static float mavlink_msg_camera_stamped_small_imu_get_zgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field zgyro from camera_stamped_small_imu message.

Returns
Angular speed around Z axis

Definition at line 355 of file mavlink_msg_camera_stamped_small_imu.h.

static uint16_t mavlink_msg_camera_stamped_small_imu_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint64_t  time_boot_us,
float  xacc,
float  yacc,
float  zacc,
float  xgyro,
float  ygyro,
float  zgyro,
float  temperature,
uint8_t  image 
)
inlinestatic

Pack a camera_stamped_small_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_boot_usMeasurement timestamp as microseconds since boot
xaccAcceleration along X axis
yaccAcceleration along Y axis
zaccAcceleration along Z axis
xgyroAngular speed around X axis
ygyroAngular speed around Y axis
zgyroAngular speed around Z axis
temperatureInternal temperature measurement
imageTrue if there is an image associated with this measurement
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 59 of file mavlink_msg_camera_stamped_small_imu.h.

static uint16_t mavlink_msg_camera_stamped_small_imu_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint64_t  time_boot_us,
float  xacc,
float  yacc,
float  zacc,
float  xgyro,
float  ygyro,
float  zgyro,
float  temperature,
uint8_t  image 
)
inlinestatic

Pack a camera_stamped_small_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_boot_usMeasurement timestamp as microseconds since boot
xaccAcceleration along X axis
yaccAcceleration along Y axis
zaccAcceleration along Z axis
xgyroAngular speed around X axis
ygyroAngular speed around Y axis
zgyroAngular speed around Z axis
temperatureInternal temperature measurement
imageTrue if there is an image associated with this measurement
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 115 of file mavlink_msg_camera_stamped_small_imu.h.



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