mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
MAVLink V2 library (auto-generated)
This commit is contained in:
parent
f58ef63cb4
commit
c644fdf9ea
132 changed files with 36223 additions and 1470 deletions
|
@ -3,7 +3,7 @@
|
|||
|
||||
#define MAVLINK_MSG_ID_LANDING_TARGET 149
|
||||
|
||||
|
||||
MAVPACKED(
|
||||
typedef struct __mavlink_landing_target_t {
|
||||
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
|
||||
float angle_x; /*< [rad] X-axis angular offset of the target from the center of the image*/
|
||||
|
@ -13,23 +13,29 @@ typedef struct __mavlink_landing_target_t {
|
|||
float size_y; /*< [rad] Size of target along y-axis*/
|
||||
uint8_t target_num; /*< The ID of the target if multiple targets are present*/
|
||||
uint8_t frame; /*< Coordinate frame used for following fields.*/
|
||||
} mavlink_landing_target_t;
|
||||
float x; /*< [m] X Position of the landing target in MAV_FRAME*/
|
||||
float y; /*< [m] Y Position of the landing target in MAV_FRAME*/
|
||||
float z; /*< [m] Z Position of the landing target in MAV_FRAME*/
|
||||
float q[4]; /*< Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
|
||||
uint8_t type; /*< Type of landing target*/
|
||||
uint8_t position_valid; /*< Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).*/
|
||||
}) mavlink_landing_target_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30
|
||||
#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 60
|
||||
#define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30
|
||||
#define MAVLINK_MSG_ID_149_LEN 30
|
||||
#define MAVLINK_MSG_ID_149_LEN 60
|
||||
#define MAVLINK_MSG_ID_149_MIN_LEN 30
|
||||
|
||||
#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200
|
||||
#define MAVLINK_MSG_ID_149_CRC 200
|
||||
|
||||
|
||||
#define MAVLINK_MSG_LANDING_TARGET_FIELD_Q_LEN 4
|
||||
|
||||
#if MAVLINK_COMMAND_24BIT
|
||||
#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \
|
||||
149, \
|
||||
"LANDING_TARGET", \
|
||||
8, \
|
||||
14, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
|
||||
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
|
||||
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
|
||||
|
@ -38,12 +44,18 @@ typedef struct __mavlink_landing_target_t {
|
|||
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
|
||||
{ "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
|
||||
{ "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
|
||||
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_landing_target_t, x) }, \
|
||||
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_landing_target_t, y) }, \
|
||||
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_landing_target_t, z) }, \
|
||||
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 42, offsetof(mavlink_landing_target_t, q) }, \
|
||||
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_landing_target_t, type) }, \
|
||||
{ "position_valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 59, offsetof(mavlink_landing_target_t, position_valid) }, \
|
||||
} \
|
||||
}
|
||||
#else
|
||||
#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \
|
||||
"LANDING_TARGET", \
|
||||
8, \
|
||||
14, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
|
||||
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
|
||||
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
|
||||
|
@ -52,6 +64,12 @@ typedef struct __mavlink_landing_target_t {
|
|||
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
|
||||
{ "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
|
||||
{ "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
|
||||
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_landing_target_t, x) }, \
|
||||
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_landing_target_t, y) }, \
|
||||
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_landing_target_t, z) }, \
|
||||
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 42, offsetof(mavlink_landing_target_t, q) }, \
|
||||
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_landing_target_t, type) }, \
|
||||
{ "position_valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 59, offsetof(mavlink_landing_target_t, position_valid) }, \
|
||||
} \
|
||||
}
|
||||
#endif
|
||||
|
@ -70,10 +88,16 @@ typedef struct __mavlink_landing_target_t {
|
|||
* @param distance [m] Distance to the target from the vehicle
|
||||
* @param size_x [rad] Size of target along x-axis
|
||||
* @param size_y [rad] Size of target along y-axis
|
||||
* @param x [m] X Position of the landing target in MAV_FRAME
|
||||
* @param y [m] Y Position of the landing target in MAV_FRAME
|
||||
* @param z [m] Z Position of the landing target in MAV_FRAME
|
||||
* @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
|
||||
* @param type Type of landing target
|
||||
* @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline 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)
|
||||
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, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
|
||||
|
@ -85,7 +109,12 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
|
|||
_mav_put_float(buf, 24, size_y);
|
||||
_mav_put_uint8_t(buf, 28, target_num);
|
||||
_mav_put_uint8_t(buf, 29, frame);
|
||||
|
||||
_mav_put_float(buf, 30, x);
|
||||
_mav_put_float(buf, 34, y);
|
||||
_mav_put_float(buf, 38, z);
|
||||
_mav_put_uint8_t(buf, 58, type);
|
||||
_mav_put_uint8_t(buf, 59, position_valid);
|
||||
_mav_put_float_array(buf, 42, q, 4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
|
||||
#else
|
||||
mavlink_landing_target_t packet;
|
||||
|
@ -97,7 +126,12 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
|
|||
packet.size_y = size_y;
|
||||
packet.target_num = target_num;
|
||||
packet.frame = frame;
|
||||
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
packet.type = type;
|
||||
packet.position_valid = position_valid;
|
||||
mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
|
||||
#endif
|
||||
|
||||
|
@ -119,11 +153,17 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
|
|||
* @param distance [m] Distance to the target from the vehicle
|
||||
* @param size_x [rad] Size of target along x-axis
|
||||
* @param size_y [rad] Size of target along y-axis
|
||||
* @param x [m] X Position of the landing target in MAV_FRAME
|
||||
* @param y [m] Y Position of the landing target in MAV_FRAME
|
||||
* @param z [m] Z Position of the landing target in MAV_FRAME
|
||||
* @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
|
||||
* @param type Type of landing target
|
||||
* @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline 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)
|
||||
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,float x,float y,float z,const float *q,uint8_t type,uint8_t position_valid)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
|
||||
|
@ -135,7 +175,12 @@ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, u
|
|||
_mav_put_float(buf, 24, size_y);
|
||||
_mav_put_uint8_t(buf, 28, target_num);
|
||||
_mav_put_uint8_t(buf, 29, frame);
|
||||
|
||||
_mav_put_float(buf, 30, x);
|
||||
_mav_put_float(buf, 34, y);
|
||||
_mav_put_float(buf, 38, z);
|
||||
_mav_put_uint8_t(buf, 58, type);
|
||||
_mav_put_uint8_t(buf, 59, position_valid);
|
||||
_mav_put_float_array(buf, 42, q, 4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
|
||||
#else
|
||||
mavlink_landing_target_t packet;
|
||||
|
@ -147,7 +192,12 @@ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, u
|
|||
packet.size_y = size_y;
|
||||
packet.target_num = target_num;
|
||||
packet.frame = frame;
|
||||
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
packet.type = type;
|
||||
packet.position_valid = position_valid;
|
||||
mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
|
||||
#endif
|
||||
|
||||
|
@ -165,7 +215,7 @@ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, u
|
|||
*/
|
||||
static inline 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)
|
||||
{
|
||||
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);
|
||||
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, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -179,7 +229,7 @@ static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint
|
|||
*/
|
||||
static inline 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)
|
||||
{
|
||||
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);
|
||||
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, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -194,10 +244,16 @@ static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id,
|
|||
* @param distance [m] Distance to the target from the vehicle
|
||||
* @param size_x [rad] Size of target along x-axis
|
||||
* @param size_y [rad] Size of target along y-axis
|
||||
* @param x [m] X Position of the landing target in MAV_FRAME
|
||||
* @param y [m] Y Position of the landing target in MAV_FRAME
|
||||
* @param z [m] Z Position of the landing target in MAV_FRAME
|
||||
* @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
|
||||
* @param type Type of landing target
|
||||
* @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, 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)
|
||||
static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, 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, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
|
||||
|
@ -209,7 +265,12 @@ static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint6
|
|||
_mav_put_float(buf, 24, size_y);
|
||||
_mav_put_uint8_t(buf, 28, target_num);
|
||||
_mav_put_uint8_t(buf, 29, frame);
|
||||
|
||||
_mav_put_float(buf, 30, x);
|
||||
_mav_put_float(buf, 34, y);
|
||||
_mav_put_float(buf, 38, z);
|
||||
_mav_put_uint8_t(buf, 58, type);
|
||||
_mav_put_uint8_t(buf, 59, position_valid);
|
||||
_mav_put_float_array(buf, 42, q, 4);
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
|
||||
#else
|
||||
mavlink_landing_target_t packet;
|
||||
|
@ -221,7 +282,12 @@ static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint6
|
|||
packet.size_y = size_y;
|
||||
packet.target_num = target_num;
|
||||
packet.frame = frame;
|
||||
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
packet.type = type;
|
||||
packet.position_valid = position_valid;
|
||||
mav_array_memcpy(packet.q, q, sizeof(float)*4);
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
|
||||
#endif
|
||||
}
|
||||
|
@ -234,7 +300,7 @@ static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint6
|
|||
static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan, const mavlink_landing_target_t* landing_target)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
mavlink_msg_landing_target_send(chan, 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);
|
||||
mavlink_msg_landing_target_send(chan, 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, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)landing_target, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
|
||||
#endif
|
||||
|
@ -248,7 +314,7 @@ static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, 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)
|
||||
static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, 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, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
|
@ -260,7 +326,12 @@ static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf
|
|||
_mav_put_float(buf, 24, size_y);
|
||||
_mav_put_uint8_t(buf, 28, target_num);
|
||||
_mav_put_uint8_t(buf, 29, frame);
|
||||
|
||||
_mav_put_float(buf, 30, x);
|
||||
_mav_put_float(buf, 34, y);
|
||||
_mav_put_float(buf, 38, z);
|
||||
_mav_put_uint8_t(buf, 58, type);
|
||||
_mav_put_uint8_t(buf, 59, position_valid);
|
||||
_mav_put_float_array(buf, 42, q, 4);
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
|
||||
#else
|
||||
mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf;
|
||||
|
@ -272,7 +343,12 @@ static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf
|
|||
packet->size_y = size_y;
|
||||
packet->target_num = target_num;
|
||||
packet->frame = frame;
|
||||
|
||||
packet->x = x;
|
||||
packet->y = y;
|
||||
packet->z = z;
|
||||
packet->type = type;
|
||||
packet->position_valid = position_valid;
|
||||
mav_array_memcpy(packet->q, q, sizeof(float)*4);
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
|
||||
#endif
|
||||
}
|
||||
|
@ -363,6 +439,66 @@ static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_
|
|||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field x from landing_target message
|
||||
*
|
||||
* @return [m] X Position of the landing target in MAV_FRAME
|
||||
*/
|
||||
static inline float mavlink_msg_landing_target_get_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 30);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field y from landing_target message
|
||||
*
|
||||
* @return [m] Y Position of the landing target in MAV_FRAME
|
||||
*/
|
||||
static inline float mavlink_msg_landing_target_get_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 34);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field z from landing_target message
|
||||
*
|
||||
* @return [m] Z Position of the landing target in MAV_FRAME
|
||||
*/
|
||||
static inline float mavlink_msg_landing_target_get_z(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 38);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field q from landing_target message
|
||||
*
|
||||
* @return Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_landing_target_get_q(const mavlink_message_t* msg, float *q)
|
||||
{
|
||||
return _MAV_RETURN_float_array(msg, q, 4, 42);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field type from landing_target message
|
||||
*
|
||||
* @return Type of landing target
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_landing_target_get_type(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 58);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field position_valid from landing_target message
|
||||
*
|
||||
* @return Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_landing_target_get_position_valid(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 59);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a landing_target message into a struct
|
||||
*
|
||||
|
@ -380,6 +516,12 @@ static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* ms
|
|||
landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg);
|
||||
landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg);
|
||||
landing_target->frame = mavlink_msg_landing_target_get_frame(msg);
|
||||
landing_target->x = mavlink_msg_landing_target_get_x(msg);
|
||||
landing_target->y = mavlink_msg_landing_target_get_y(msg);
|
||||
landing_target->z = mavlink_msg_landing_target_get_z(msg);
|
||||
mavlink_msg_landing_target_get_q(msg, landing_target->q);
|
||||
landing_target->type = mavlink_msg_landing_target_get_type(msg);
|
||||
landing_target->position_valid = mavlink_msg_landing_target_get_position_valid(msg);
|
||||
#else
|
||||
uint8_t len = msg->len < MAVLINK_MSG_ID_LANDING_TARGET_LEN? msg->len : MAVLINK_MSG_ID_LANDING_TARGET_LEN;
|
||||
memset(landing_target, 0, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue