mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 09:16:01 +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_RAW_IMU 27
|
||||
|
||||
|
||||
MAVPACKED(
|
||||
typedef struct __mavlink_raw_imu_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.*/
|
||||
int16_t xacc; /*< X acceleration (raw)*/
|
||||
|
@ -15,11 +15,13 @@ typedef struct __mavlink_raw_imu_t {
|
|||
int16_t xmag; /*< X Magnetic field (raw)*/
|
||||
int16_t ymag; /*< Y Magnetic field (raw)*/
|
||||
int16_t zmag; /*< Z Magnetic field (raw)*/
|
||||
} mavlink_raw_imu_t;
|
||||
uint8_t id; /*< Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)*/
|
||||
int16_t temperature; /*< [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).*/
|
||||
}) mavlink_raw_imu_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_RAW_IMU_LEN 26
|
||||
#define MAVLINK_MSG_ID_RAW_IMU_LEN 29
|
||||
#define MAVLINK_MSG_ID_RAW_IMU_MIN_LEN 26
|
||||
#define MAVLINK_MSG_ID_27_LEN 26
|
||||
#define MAVLINK_MSG_ID_27_LEN 29
|
||||
#define MAVLINK_MSG_ID_27_MIN_LEN 26
|
||||
|
||||
#define MAVLINK_MSG_ID_RAW_IMU_CRC 144
|
||||
|
@ -31,7 +33,7 @@ typedef struct __mavlink_raw_imu_t {
|
|||
#define MAVLINK_MESSAGE_INFO_RAW_IMU { \
|
||||
27, \
|
||||
"RAW_IMU", \
|
||||
10, \
|
||||
12, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \
|
||||
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
|
||||
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
|
||||
|
@ -42,12 +44,14 @@ typedef struct __mavlink_raw_imu_t {
|
|||
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
|
||||
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
|
||||
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
|
||||
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_raw_imu_t, id) }, \
|
||||
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_raw_imu_t, temperature) }, \
|
||||
} \
|
||||
}
|
||||
#else
|
||||
#define MAVLINK_MESSAGE_INFO_RAW_IMU { \
|
||||
"RAW_IMU", \
|
||||
10, \
|
||||
12, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \
|
||||
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
|
||||
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
|
||||
|
@ -58,6 +62,8 @@ typedef struct __mavlink_raw_imu_t {
|
|||
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
|
||||
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
|
||||
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
|
||||
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_raw_imu_t, id) }, \
|
||||
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_raw_imu_t, temperature) }, \
|
||||
} \
|
||||
}
|
||||
#endif
|
||||
|
@ -78,10 +84,12 @@ typedef struct __mavlink_raw_imu_t {
|
|||
* @param xmag X Magnetic field (raw)
|
||||
* @param ymag Y Magnetic field (raw)
|
||||
* @param zmag Z Magnetic field (raw)
|
||||
* @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
|
||||
* @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
|
||||
uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, uint8_t id, int16_t temperature)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_RAW_IMU_LEN];
|
||||
|
@ -95,6 +103,8 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
|
|||
_mav_put_int16_t(buf, 20, xmag);
|
||||
_mav_put_int16_t(buf, 22, ymag);
|
||||
_mav_put_int16_t(buf, 24, zmag);
|
||||
_mav_put_uint8_t(buf, 26, id);
|
||||
_mav_put_int16_t(buf, 27, temperature);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN);
|
||||
#else
|
||||
|
@ -109,6 +119,8 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
|
|||
packet.xmag = xmag;
|
||||
packet.ymag = ymag;
|
||||
packet.zmag = zmag;
|
||||
packet.id = id;
|
||||
packet.temperature = temperature;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN);
|
||||
#endif
|
||||
|
@ -133,11 +145,13 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
|
|||
* @param xmag X Magnetic field (raw)
|
||||
* @param ymag Y Magnetic field (raw)
|
||||
* @param zmag Z Magnetic field (raw)
|
||||
* @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
|
||||
* @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
|
||||
uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag,uint8_t id,int16_t temperature)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_RAW_IMU_LEN];
|
||||
|
@ -151,6 +165,8 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t
|
|||
_mav_put_int16_t(buf, 20, xmag);
|
||||
_mav_put_int16_t(buf, 22, ymag);
|
||||
_mav_put_int16_t(buf, 24, zmag);
|
||||
_mav_put_uint8_t(buf, 26, id);
|
||||
_mav_put_int16_t(buf, 27, temperature);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN);
|
||||
#else
|
||||
|
@ -165,6 +181,8 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t
|
|||
packet.xmag = xmag;
|
||||
packet.ymag = ymag;
|
||||
packet.zmag = zmag;
|
||||
packet.id = id;
|
||||
packet.temperature = temperature;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN);
|
||||
#endif
|
||||
|
@ -183,7 +201,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
|
||||
{
|
||||
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
|
||||
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag, raw_imu->id, raw_imu->temperature);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -197,7 +215,7 @@ static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t com
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
|
||||
{
|
||||
return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
|
||||
return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag, raw_imu->id, raw_imu->temperature);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -214,10 +232,12 @@ static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_
|
|||
* @param xmag X Magnetic field (raw)
|
||||
* @param ymag Y Magnetic field (raw)
|
||||
* @param zmag Z Magnetic field (raw)
|
||||
* @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
|
||||
* @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
|
||||
static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, uint8_t id, int16_t temperature)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_RAW_IMU_LEN];
|
||||
|
@ -231,6 +251,8 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t tim
|
|||
_mav_put_int16_t(buf, 20, xmag);
|
||||
_mav_put_int16_t(buf, 22, ymag);
|
||||
_mav_put_int16_t(buf, 24, zmag);
|
||||
_mav_put_uint8_t(buf, 26, id);
|
||||
_mav_put_int16_t(buf, 27, temperature);
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
|
||||
#else
|
||||
|
@ -245,6 +267,8 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t tim
|
|||
packet.xmag = xmag;
|
||||
packet.ymag = ymag;
|
||||
packet.zmag = zmag;
|
||||
packet.id = id;
|
||||
packet.temperature = temperature;
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
|
||||
#endif
|
||||
|
@ -258,7 +282,7 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t tim
|
|||
static inline void mavlink_msg_raw_imu_send_struct(mavlink_channel_t chan, const mavlink_raw_imu_t* raw_imu)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
mavlink_msg_raw_imu_send(chan, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
|
||||
mavlink_msg_raw_imu_send(chan, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag, raw_imu->id, raw_imu->temperature);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)raw_imu, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
|
||||
#endif
|
||||
|
@ -272,7 +296,7 @@ static inline void mavlink_msg_raw_imu_send_struct(mavlink_channel_t chan, const
|
|||
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_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
|
||||
static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, uint8_t id, int16_t temperature)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
|
@ -286,6 +310,8 @@ static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavli
|
|||
_mav_put_int16_t(buf, 20, xmag);
|
||||
_mav_put_int16_t(buf, 22, ymag);
|
||||
_mav_put_int16_t(buf, 24, zmag);
|
||||
_mav_put_uint8_t(buf, 26, id);
|
||||
_mav_put_int16_t(buf, 27, temperature);
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
|
||||
#else
|
||||
|
@ -300,6 +326,8 @@ static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavli
|
|||
packet->xmag = xmag;
|
||||
packet->ymag = ymag;
|
||||
packet->zmag = zmag;
|
||||
packet->id = id;
|
||||
packet->temperature = temperature;
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
|
||||
#endif
|
||||
|
@ -411,6 +439,26 @@ static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg)
|
|||
return _MAV_RETURN_int16_t(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field id from raw_imu message
|
||||
*
|
||||
* @return Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_raw_imu_get_id(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 26);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field temperature from raw_imu message
|
||||
*
|
||||
* @return [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
|
||||
*/
|
||||
static inline int16_t mavlink_msg_raw_imu_get_temperature(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 27);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a raw_imu message into a struct
|
||||
*
|
||||
|
@ -430,6 +478,8 @@ static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavl
|
|||
raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg);
|
||||
raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg);
|
||||
raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg);
|
||||
raw_imu->id = mavlink_msg_raw_imu_get_id(msg);
|
||||
raw_imu->temperature = mavlink_msg_raw_imu_get_temperature(msg);
|
||||
#else
|
||||
uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_IMU_LEN? msg->len : MAVLINK_MSG_ID_RAW_IMU_LEN;
|
||||
memset(raw_imu, 0, MAVLINK_MSG_ID_RAW_IMU_LEN);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue