3 #define MAVLINK_MSG_ID_LANDING_TARGET 149 17 #define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30 18 #define MAVLINK_MSG_ID_149_LEN 30 20 #define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200 21 #define MAVLINK_MSG_ID_149_CRC 200 25 #define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ 28 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ 29 { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ 30 { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ 31 { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ 32 { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ 33 { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ 34 { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ 35 { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ 59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 110 mavlink_message_t* msg,
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 140 #if MAVLINK_CRC_EXTRA 157 return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->
time_usec, landing_target->
target_num, landing_target->
frame, landing_target->
angle_x, landing_target->
angle_y, landing_target->
distance, landing_target->
size_x, landing_target->
size_y);
171 return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->
time_usec, landing_target->
target_num, landing_target->
frame, landing_target->
angle_x, landing_target->
angle_y, landing_target->
distance, landing_target->
size_x, landing_target->
size_y);
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 202 #if MAVLINK_CRC_EXTRA 218 #if MAVLINK_CRC_EXTRA 226 #if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN 236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 237 char *buf = (
char *)msgbuf;
247 #if MAVLINK_CRC_EXTRA 263 #if MAVLINK_CRC_EXTRA 284 return _MAV_RETURN_uint64_t(msg, 0);
314 return _MAV_RETURN_float(msg, 8);
324 return _MAV_RETURN_float(msg, 12);
334 return _MAV_RETURN_float(msg, 16);
344 return _MAV_RETURN_float(msg, 20);
354 return _MAV_RETURN_float(msg, 24);
365 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_landing_target_t *landing_target)
Encode a landing_target struct on a channel.
#define _mav_put_float(buf, wire_offset, b)
static uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t *msg)
Send a landing_target message.
static uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
Pack a landing_target message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
#define MAVLINK_MSG_ID_LANDING_TARGET_LEN
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 _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_landing_target_get_size_x(const mavlink_message_t *msg)
Get field size_x from landing_target message.
static float mavlink_msg_landing_target_get_size_y(const mavlink_message_t *msg)
Get field size_y from landing_target message.
static uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t *msg)
Get field target_num from landing_target message.
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t *msg)
Get field angle_y from landing_target message.
static float mavlink_msg_landing_target_get_distance(const mavlink_message_t *msg)
Get field distance from landing_target message.
#define MAVLINK_MSG_ID_LANDING_TARGET
struct __mavlink_landing_target_t mavlink_landing_target_t
static uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t *msg)
Get field frame from landing_target message.
static float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t *msg)
Get field angle_x from landing_target message.
static uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
Pack a landing_target message on a channel.
#define MAVLINK_MSG_ID_LANDING_TARGET_CRC
static void mavlink_msg_landing_target_decode(const mavlink_message_t *msg, mavlink_landing_target_t *landing_target)
Decode a landing_target message into a struct.
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.
static uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_landing_target_t *landing_target)
Encode a landing_target struct.