Classes | Macros | Typedefs | Functions
mavlink_msg_local_position_ned_system_global_offset.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_local_position_ned_system_global_offset_t
 

Macros

#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET
 
#define MAVLINK_MSG_ID_89_CRC   231
 
#define MAVLINK_MSG_ID_89_LEN   28
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET   89
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC   231
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN   28
 

Typedefs

typedef struct __mavlink_local_position_ned_system_global_offset_t mavlink_local_position_ned_system_global_offset_t
 

Functions

static void mavlink_msg_local_position_ned_system_global_offset_decode (const mavlink_message_t *msg, mavlink_local_position_ned_system_global_offset_t *local_position_ned_system_global_offset)
 Decode a local_position_ned_system_global_offset message into a struct. More...
 
static uint16_t mavlink_msg_local_position_ned_system_global_offset_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_local_position_ned_system_global_offset_t *local_position_ned_system_global_offset)
 Encode a local_position_ned_system_global_offset struct. More...
 
static uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_local_position_ned_system_global_offset_t *local_position_ned_system_global_offset)
 Encode a local_position_ned_system_global_offset struct on a channel. More...
 
static float mavlink_msg_local_position_ned_system_global_offset_get_pitch (const mavlink_message_t *msg)
 Get field pitch from local_position_ned_system_global_offset message. More...
 
static float mavlink_msg_local_position_ned_system_global_offset_get_roll (const mavlink_message_t *msg)
 Get field roll from local_position_ned_system_global_offset message. More...
 
static uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms (const mavlink_message_t *msg)
 Send a local_position_ned_system_global_offset message. More...
 
static float mavlink_msg_local_position_ned_system_global_offset_get_x (const mavlink_message_t *msg)
 Get field x from local_position_ned_system_global_offset message. More...
 
static float mavlink_msg_local_position_ned_system_global_offset_get_y (const mavlink_message_t *msg)
 Get field y from local_position_ned_system_global_offset message. More...
 
static float mavlink_msg_local_position_ned_system_global_offset_get_yaw (const mavlink_message_t *msg)
 Get field yaw from local_position_ned_system_global_offset message. More...
 
static float mavlink_msg_local_position_ned_system_global_offset_get_z (const mavlink_message_t *msg)
 Get field z from local_position_ned_system_global_offset message. More...
 
static uint16_t mavlink_msg_local_position_ned_system_global_offset_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw)
 Pack a local_position_ned_system_global_offset message. More...
 
static uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw)
 Pack a local_position_ned_system_global_offset message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET
#define MAVLINK_MSG_ID_89_CRC   231
#define MAVLINK_MSG_ID_89_LEN   28
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET   89
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC   231
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN   28

Typedef Documentation

Function Documentation

static void mavlink_msg_local_position_ned_system_global_offset_decode ( const mavlink_message_t *  msg,
mavlink_local_position_ned_system_global_offset_t local_position_ned_system_global_offset 
)
inlinestatic

Decode a local_position_ned_system_global_offset message into a struct.

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

Definition at line 340 of file mavlink_msg_local_position_ned_system_global_offset.h.

static uint16_t mavlink_msg_local_position_ned_system_global_offset_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_local_position_ned_system_global_offset_t local_position_ned_system_global_offset 
)
inlinestatic

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

Definition at line 147 of file mavlink_msg_local_position_ned_system_global_offset.h.

static uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_local_position_ned_system_global_offset_t local_position_ned_system_global_offset 
)
inlinestatic

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

Definition at line 161 of file mavlink_msg_local_position_ned_system_global_offset.h.

static float mavlink_msg_local_position_ned_system_global_offset_get_pitch ( const mavlink_message_t *  msg)
inlinestatic

Get field pitch from local_position_ned_system_global_offset message.

Returns
Pitch

Definition at line 319 of file mavlink_msg_local_position_ned_system_global_offset.h.

static float mavlink_msg_local_position_ned_system_global_offset_get_roll ( const mavlink_message_t *  msg)
inlinestatic

Get field roll from local_position_ned_system_global_offset message.

Returns
Roll

Definition at line 309 of file mavlink_msg_local_position_ned_system_global_offset.h.

static uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a local_position_ned_system_global_offset message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
xX Position
yY Position
zZ Position
rollRoll
pitchPitch
yawYaw Get field time_boot_ms from local_position_ned_system_global_offset message
Returns
Timestamp (milliseconds since system boot)

Definition at line 269 of file mavlink_msg_local_position_ned_system_global_offset.h.

static float mavlink_msg_local_position_ned_system_global_offset_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from local_position_ned_system_global_offset message.

Returns
X Position

Definition at line 279 of file mavlink_msg_local_position_ned_system_global_offset.h.

static float mavlink_msg_local_position_ned_system_global_offset_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from local_position_ned_system_global_offset message.

Returns
Y Position

Definition at line 289 of file mavlink_msg_local_position_ned_system_global_offset.h.

static float mavlink_msg_local_position_ned_system_global_offset_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from local_position_ned_system_global_offset message.

Returns
Yaw

Definition at line 329 of file mavlink_msg_local_position_ned_system_global_offset.h.

static float mavlink_msg_local_position_ned_system_global_offset_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from local_position_ned_system_global_offset message.

Returns
Z Position

Definition at line 299 of file mavlink_msg_local_position_ned_system_global_offset.h.

static uint16_t mavlink_msg_local_position_ned_system_global_offset_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw 
)
inlinestatic

Pack a local_position_ned_system_global_offset 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)
xX Position
yY Position
zZ Position
rollRoll
pitchPitch
yawYaw
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_local_position_ned_system_global_offset.h.

static uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw 
)
inlinestatic

Pack a local_position_ned_system_global_offset 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)
xX Position
yY Position
zZ Position
rollRoll
pitchPitch
yawYaw
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_local_position_ned_system_global_offset.h.



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