Classes | Macros | Typedefs | Functions
mavlink_msg_local_position_ned.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_t
 

Macros

#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED
 
#define MAVLINK_MSG_ID_32_CRC   185
 
#define MAVLINK_MSG_ID_32_LEN   28
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED   32
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC   185
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN   28
 

Typedefs

typedef struct __mavlink_local_position_ned_t mavlink_local_position_ned_t
 

Functions

static void mavlink_msg_local_position_ned_decode (const mavlink_message_t *msg, mavlink_local_position_ned_t *local_position_ned)
 Decode a local_position_ned message into a struct. More...
 
static uint16_t mavlink_msg_local_position_ned_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_local_position_ned_t *local_position_ned)
 Encode a local_position_ned struct. More...
 
static uint16_t mavlink_msg_local_position_ned_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_local_position_ned_t *local_position_ned)
 Encode a local_position_ned struct on a channel. More...
 
static uint32_t mavlink_msg_local_position_ned_get_time_boot_ms (const mavlink_message_t *msg)
 Send a local_position_ned message. More...
 
static float mavlink_msg_local_position_ned_get_vx (const mavlink_message_t *msg)
 Get field vx from local_position_ned message. More...
 
static float mavlink_msg_local_position_ned_get_vy (const mavlink_message_t *msg)
 Get field vy from local_position_ned message. More...
 
static float mavlink_msg_local_position_ned_get_vz (const mavlink_message_t *msg)
 Get field vz from local_position_ned message. More...
 
static float mavlink_msg_local_position_ned_get_x (const mavlink_message_t *msg)
 Get field x from local_position_ned message. More...
 
static float mavlink_msg_local_position_ned_get_y (const mavlink_message_t *msg)
 Get field y from local_position_ned message. More...
 
static float mavlink_msg_local_position_ned_get_z (const mavlink_message_t *msg)
 Get field z from local_position_ned message. More...
 
static uint16_t mavlink_msg_local_position_ned_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 vx, float vy, float vz)
 Pack a local_position_ned message. More...
 
static uint16_t mavlink_msg_local_position_ned_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 vx, float vy, float vz)
 Pack a local_position_ned message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED
Value:
{ \
"LOCAL_POSITION_NED", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_local_position_ned.h.

#define MAVLINK_MSG_ID_32_CRC   185

Definition at line 20 of file mavlink_msg_local_position_ned.h.

#define MAVLINK_MSG_ID_32_LEN   28

Definition at line 17 of file mavlink_msg_local_position_ned.h.

#define MAVLINK_MSG_ID_LOCAL_POSITION_NED   32

Definition at line 3 of file mavlink_msg_local_position_ned.h.

#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC   185

Definition at line 19 of file mavlink_msg_local_position_ned.h.

#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN   28

Definition at line 16 of file mavlink_msg_local_position_ned.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_local_position_ned_decode ( const mavlink_message_t *  msg,
mavlink_local_position_ned_t local_position_ned 
)
inlinestatic

Decode a local_position_ned message into a struct.

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

Definition at line 340 of file mavlink_msg_local_position_ned.h.

static uint16_t mavlink_msg_local_position_ned_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_local_position_ned_t local_position_ned 
)
inlinestatic

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

Definition at line 147 of file mavlink_msg_local_position_ned.h.

static uint16_t mavlink_msg_local_position_ned_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_local_position_ned_t local_position_ned 
)
inlinestatic

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

Definition at line 161 of file mavlink_msg_local_position_ned.h.

static uint32_t mavlink_msg_local_position_ned_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a local_position_ned message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
xX Position
yY Position
zZ Position
vxX Speed
vyY Speed
vzZ Speed Get field time_boot_ms from local_position_ned message
Returns
Timestamp (milliseconds since system boot)

Definition at line 269 of file mavlink_msg_local_position_ned.h.

static float mavlink_msg_local_position_ned_get_vx ( const mavlink_message_t *  msg)
inlinestatic

Get field vx from local_position_ned message.

Returns
X Speed

Definition at line 309 of file mavlink_msg_local_position_ned.h.

static float mavlink_msg_local_position_ned_get_vy ( const mavlink_message_t *  msg)
inlinestatic

Get field vy from local_position_ned message.

Returns
Y Speed

Definition at line 319 of file mavlink_msg_local_position_ned.h.

static float mavlink_msg_local_position_ned_get_vz ( const mavlink_message_t *  msg)
inlinestatic

Get field vz from local_position_ned message.

Returns
Z Speed

Definition at line 329 of file mavlink_msg_local_position_ned.h.

static float mavlink_msg_local_position_ned_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from local_position_ned message.

Returns
X Position

Definition at line 279 of file mavlink_msg_local_position_ned.h.

static float mavlink_msg_local_position_ned_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from local_position_ned message.

Returns
Y Position

Definition at line 289 of file mavlink_msg_local_position_ned.h.

static float mavlink_msg_local_position_ned_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from local_position_ned message.

Returns
Z Position

Definition at line 299 of file mavlink_msg_local_position_ned.h.

static uint16_t mavlink_msg_local_position_ned_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  vx,
float  vy,
float  vz 
)
inlinestatic

Pack a local_position_ned 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
vxX Speed
vyY Speed
vzZ Speed
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_local_position_ned.h.

static uint16_t mavlink_msg_local_position_ned_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  vx,
float  vy,
float  vz 
)
inlinestatic

Pack a local_position_ned 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
vxX Speed
vyY Speed
vzZ Speed
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_local_position_ned.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:27