【类 型】:feat 修改mavlink底层库 (注意这个版本是有bug的 未完成状态)

【原  因】:添加 向飞控请求 飞机home点 的 id常量定义 封装打包函数 解包函数等
【过  程】:
【影  响】:

# 类型 包含:
# feat:新功能(feature)
# fix:修补bug
# docs:文档(documentation)
# style: 格式(不影响代码运行的变动)
# refactor:重构(即不是新增功能,也不是修改bug的代码变动)
# test:增加测试
# chore:构建过程或辅助工具的变动
This commit is contained in:
tk 2024-07-26 23:37:50 +08:00
parent 5d8f28e545
commit b4b175b316
2 changed files with 170 additions and 106 deletions

View File

@ -17,12 +17,12 @@ typedef struct __mavlink_attitude_quaternion_t
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
#define MAVLINK_MSG_ID_31_LEN 32
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION \
{ \
"ATTITUDE_QUATERNION", \
8, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
{ \
{"time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms)}, \
{"q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1)}, \
{"q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2)}, \
{"q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3)}, \
@ -33,7 +33,6 @@ typedef struct __mavlink_attitude_quaternion_t
} \
}
/**
* @brief Pack a attitude_quaternion message
* @param system_id ID of this system
@ -194,7 +193,6 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan,
// MESSAGE ATTITUDE_QUATERNION UNPACKING
/**
* @brief Get field time_boot_ms from attitude_quaternion message
*

View File

@ -18,12 +18,12 @@ typedef struct __mavlink_global_position_int_t
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
#define MAVLINK_MSG_ID_33_LEN 28
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT \
{ \
"GLOBAL_POSITION_INT", \
9, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
{ \
{"time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms)}, \
{"lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat)}, \
{"lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon)}, \
{"alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt)}, \
@ -35,7 +35,6 @@ typedef struct __mavlink_global_position_int_t
} \
}
/**
* @brief Pack a global_position_int message
* @param system_id ID of this system
@ -205,7 +204,6 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan,
// MESSAGE GLOBAL_POSITION_INT UNPACKING
/**
* @brief Get field time_boot_ms from global_position_int message
*
@ -318,3 +316,71 @@ static inline void mavlink_msg_global_position_int_decode(const mavlink_message_
memcpy(global_position_int, _MAV_PAYLOAD(msg), 28);
#endif
}
/**
* @brief Pack a home_position message
* @param system_id ID of this system
* @param component_id ID of this component
* @param msg The MAVLink message to compress the data into
* @param home_position C-struct to read the message contents from
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_home_position_t *home_position)
{
char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
_mav_put_int32_t(buf, 0, home_position->latitude);
_mav_put_int32_t(buf, 4, home_position->longitude);
_mav_put_int32_t(buf, 8, home_position->altitude);
_mav_put_float(buf, 12, home_position->x);
_mav_put_float(buf, 16, home_position->y);
_mav_put_float(buf, 20, home_position->z);
_mav_put_float_array(buf, 24, home_position->q, 4);
_mav_put_float(buf, 40, home_position->approach_x);
_mav_put_float(buf, 44, home_position->approach_y);
_mav_put_float(buf, 48, home_position->approach_z);
_mav_put_uint64_t(buf, 52, home_position->time_usec);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN, 0);
}
/**
* @brief Decode a home_position message into a struct
* @param msg The message to decode
* @param home_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_home_position_decode(const mavlink_message_t *msg, mavlink_home_position_t *home_position)
{
#if MAVLINK_NEED_BYTE_SWAP
home_position->latitude = mavlink_msg_home_position_get_latitude(msg);
home_position->longitude = mavlink_msg_home_position_get_longitude(msg);
home_position->altitude = mavlink_msg_home_position_get_altitude(msg);
home_position->x = mavlink_msg_home_position_get_x(msg);
home_position->y = mavlink_msg_home_position_get_y(msg);
home_position->z = mavlink_msg_home_position_get_z(msg);
mavlink_msg_home_position_get_q(msg, home_position->q);
home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg);
home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg);
home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg);
home_position->time_usec = mavlink_msg_home_position_get_time_usec(msg);
#else
memcpy(home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HOME_POSITION_LEN);
#endif
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a home_position message
* @param chan MAVLink channel to send the message
* @param home_position C-struct to send the message contents from
*/
static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, const mavlink_home_position_t *home_position)
{
mavlink_message_t msg;
mavlink_msg_home_position_pack_chan(0, 0, chan, &msg, home_position);
mavlink_send_uart(chan, &msg);
}
#endif