3 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 16 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 17 #define MAVLINK_MSG_ID_32_LEN 28 19 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 20 #define MAVLINK_MSG_ID_32_CRC 185 24 #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ 25 "LOCAL_POSITION_NED", \ 27 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ 28 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ 29 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ 30 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ 31 { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ 32 { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ 33 { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ 56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 104 mavlink_message_t* msg,
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 132 #if MAVLINK_CRC_EXTRA 163 return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->
time_boot_ms, local_position_ned->
x, local_position_ned->
y, local_position_ned->
z, local_position_ned->
vx, local_position_ned->
vy, local_position_ned->
vz);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 192 #if MAVLINK_CRC_EXTRA 207 #if MAVLINK_CRC_EXTRA 215 #if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN 223 static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t
time_boot_ms,
float x,
float y,
float z,
float vx,
float vy,
float vz)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA 250 #if MAVLINK_CRC_EXTRA 271 return _MAV_RETURN_uint32_t(msg, 0);
281 return _MAV_RETURN_float(msg, 4);
291 return _MAV_RETURN_float(msg, 8);
301 return _MAV_RETURN_float(msg, 12);
311 return _MAV_RETURN_float(msg, 16);
321 return _MAV_RETURN_float(msg, 20);
331 return _MAV_RETURN_float(msg, 24);
342 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static float mavlink_msg_local_position_ned_get_x(const mavlink_message_t *msg)
Get field x from local_position_ned message.
static float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t *msg)
Get field vz from local_position_ned message.
static uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t *msg)
Send a local_position_ned message.
static float mavlink_msg_local_position_ned_get_y(const mavlink_message_t *msg)
Get field y from local_position_ned message.
static float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t *msg)
Get field vx from local_position_ned message.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC
#define _MAV_PAYLOAD_NON_CONST(msg)
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.
struct __mavlink_local_position_ned_t mavlink_local_position_ned_t
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.
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t *msg)
Get field vy from local_position_ned message.
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.
static float mavlink_msg_local_position_ned_get_z(const mavlink_message_t *msg)
Get field z from local_position_ned message.
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.
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.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN
#define _mav_put_uint32_t(buf, wire_offset, b)