【类 型】:feat 修改mavlink底层库 (注意这个版本是有bug的 未完成状态)
【原 因】:添加 向飞控请求 飞机home点 的 id常量定义 封装打包函数 解包函数等 【过 程】: 【影 响】: # 类型 包含: # feat:新功能(feature) # fix:修补bug # docs:文档(documentation) # style: 格式(不影响代码运行的变动) # refactor:重构(即不是新增功能,也不是修改bug的代码变动) # test:增加测试 # chore:构建过程或辅助工具的变动
This commit is contained in:
parent
5d8f28e545
commit
b4b175b316
@ -4,35 +4,34 @@
|
||||
|
||||
typedef struct __mavlink_attitude_quaternion_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
float q1; ///< Quaternion component 1
|
||||
float q2; ///< Quaternion component 2
|
||||
float q3; ///< Quaternion component 3
|
||||
float q4; ///< Quaternion component 4
|
||||
float rollspeed; ///< Roll angular speed (rad/s)
|
||||
float pitchspeed; ///< Pitch angular speed (rad/s)
|
||||
float yawspeed; ///< Yaw angular speed (rad/s)
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
float q1; ///< Quaternion component 1
|
||||
float q2; ///< Quaternion component 2
|
||||
float q3; ///< Quaternion component 3
|
||||
float q4; ///< Quaternion component 4
|
||||
float rollspeed; ///< Roll angular speed (rad/s)
|
||||
float pitchspeed; ///< Pitch angular speed (rad/s)
|
||||
float yawspeed; ///< Yaw angular speed (rad/s)
|
||||
} 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 { \
|
||||
"ATTITUDE_QUATERNION", \
|
||||
8, \
|
||||
{ { "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) }, \
|
||||
{ "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
|
||||
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
|
||||
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
|
||||
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
#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)}, \
|
||||
{"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)}, \
|
||||
{"q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4)}, \
|
||||
{"rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed)}, \
|
||||
{"pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed)}, \
|
||||
{"yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed)}, \
|
||||
} \
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a attitude_quaternion message
|
||||
@ -50,8 +49,8 @@ typedef struct __mavlink_attitude_quaternion_t
|
||||
* @param yawspeed Yaw angular speed (rad/s)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
|
||||
static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg,
|
||||
uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[32];
|
||||
@ -64,7 +63,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
|
||||
_mav_put_float(buf, 24, pitchspeed);
|
||||
_mav_put_float(buf, 28, yawspeed);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
|
||||
#else
|
||||
mavlink_attitude_quaternion_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
@ -76,7 +75,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
|
||||
packet.pitchspeed = pitchspeed;
|
||||
packet.yawspeed = yawspeed;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
|
||||
@ -100,8 +99,8 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed)
|
||||
mavlink_message_t *msg,
|
||||
uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[32];
|
||||
@ -114,7 +113,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
|
||||
_mav_put_float(buf, 24, pitchspeed);
|
||||
_mav_put_float(buf, 28, yawspeed);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
|
||||
#else
|
||||
mavlink_attitude_quaternion_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
@ -126,7 +125,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
|
||||
packet.pitchspeed = pitchspeed;
|
||||
packet.yawspeed = yawspeed;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
|
||||
@ -141,7 +140,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param attitude_quaternion C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
|
||||
static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_attitude_quaternion_t *attitude_quaternion)
|
||||
{
|
||||
return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
|
||||
}
|
||||
@ -194,15 +193,14 @@ 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
|
||||
*
|
||||
* @return Timestamp (milliseconds since system boot)
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg)
|
||||
static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 0);
|
||||
return _MAV_RETURN_uint32_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -210,9 +208,9 @@ static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const ma
|
||||
*
|
||||
* @return Quaternion component 1
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -220,9 +218,9 @@ static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message
|
||||
*
|
||||
* @return Quaternion component 2
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -230,9 +228,9 @@ static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message
|
||||
*
|
||||
* @return Quaternion component 3
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -240,9 +238,9 @@ static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message
|
||||
*
|
||||
* @return Quaternion component 4
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -250,9 +248,9 @@ static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message
|
||||
*
|
||||
* @return Roll angular speed (rad/s)
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -260,9 +258,9 @@ static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_
|
||||
*
|
||||
* @return Pitch angular speed (rad/s)
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -270,9 +268,9 @@ static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink
|
||||
*
|
||||
* @return Yaw angular speed (rad/s)
|
||||
*/
|
||||
static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -281,7 +279,7 @@ static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_m
|
||||
* @param msg The message to decode
|
||||
* @param attitude_quaternion C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion)
|
||||
static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t *msg, mavlink_attitude_quaternion_t *attitude_quaternion)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg);
|
||||
|
@ -4,37 +4,36 @@
|
||||
|
||||
typedef struct __mavlink_global_position_int_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
int32_t lat; ///< Latitude, expressed as * 1E7
|
||||
int32_t lon; ///< Longitude, expressed as * 1E7
|
||||
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
||||
int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
|
||||
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
|
||||
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
int32_t lat; ///< Latitude, expressed as * 1E7
|
||||
int32_t lon; ///< Longitude, expressed as * 1E7
|
||||
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
||||
int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
|
||||
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
|
||||
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
} 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 { \
|
||||
"GLOBAL_POSITION_INT", \
|
||||
9, \
|
||||
{ { "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) }, \
|
||||
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
|
||||
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
|
||||
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
|
||||
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
|
||||
{ "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
#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)}, \
|
||||
{"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)}, \
|
||||
{"relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt)}, \
|
||||
{"vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx)}, \
|
||||
{"vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy)}, \
|
||||
{"vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz)}, \
|
||||
{"hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg)}, \
|
||||
} \
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a global_position_int message
|
||||
@ -53,8 +52,8 @@ typedef struct __mavlink_global_position_int_t
|
||||
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
|
||||
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg,
|
||||
uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[28];
|
||||
@ -68,7 +67,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
|
||||
_mav_put_int16_t(buf, 24, vz);
|
||||
_mav_put_uint16_t(buf, 26, hdg);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
|
||||
#else
|
||||
mavlink_global_position_int_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
@ -81,7 +80,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
|
||||
packet.vz = vz;
|
||||
packet.hdg = hdg;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
|
||||
@ -106,8 +105,8 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
|
||||
mavlink_message_t *msg,
|
||||
uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[28];
|
||||
@ -121,7 +120,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
|
||||
_mav_put_int16_t(buf, 24, vz);
|
||||
_mav_put_uint16_t(buf, 26, hdg);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
|
||||
#else
|
||||
mavlink_global_position_int_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
@ -134,7 +133,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
|
||||
packet.vz = vz;
|
||||
packet.hdg = hdg;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
|
||||
@ -149,7 +148,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param global_position_int C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
|
||||
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_global_position_int_t *global_position_int)
|
||||
{
|
||||
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
|
||||
}
|
||||
@ -205,15 +204,14 @@ 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
|
||||
*
|
||||
* @return Timestamp (milliseconds since system boot)
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
|
||||
static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 0);
|
||||
return _MAV_RETURN_uint32_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -221,9 +219,9 @@ static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const ma
|
||||
*
|
||||
* @return Latitude, expressed as * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
|
||||
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 4);
|
||||
return _MAV_RETURN_int32_t(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -231,9 +229,9 @@ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_mess
|
||||
*
|
||||
* @return Longitude, expressed as * 1E7
|
||||
*/
|
||||
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
|
||||
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 8);
|
||||
return _MAV_RETURN_int32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -241,9 +239,9 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
|
||||
*
|
||||
* @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
|
||||
*/
|
||||
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
|
||||
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 12);
|
||||
return _MAV_RETURN_int32_t(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -251,9 +249,9 @@ static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_mess
|
||||
*
|
||||
* @return Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||
*/
|
||||
static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
|
||||
static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 16);
|
||||
return _MAV_RETURN_int32_t(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -261,9 +259,9 @@ static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mav
|
||||
*
|
||||
* @return Ground X Speed (Latitude), expressed as m/s * 100
|
||||
*/
|
||||
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
|
||||
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 20);
|
||||
return _MAV_RETURN_int16_t(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -271,9 +269,9 @@ static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_messa
|
||||
*
|
||||
* @return Ground Y Speed (Longitude), expressed as m/s * 100
|
||||
*/
|
||||
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
|
||||
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 22);
|
||||
return _MAV_RETURN_int16_t(msg, 22);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -281,9 +279,9 @@ static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_messa
|
||||
*
|
||||
* @return Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
*/
|
||||
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
|
||||
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 24);
|
||||
return _MAV_RETURN_int16_t(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -291,9 +289,9 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa
|
||||
*
|
||||
* @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
|
||||
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t *msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 26);
|
||||
return _MAV_RETURN_uint16_t(msg, 26);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -302,7 +300,7 @@ static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_mes
|
||||
* @param msg The message to decode
|
||||
* @param global_position_int C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
|
||||
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t *msg, mavlink_global_position_int_t *global_position_int)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg);
|
||||
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user