Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • avn/swd/mavlink/mavlink-skyward-lib
1 result
Show changes
Commits on Source (33)
Showing
with 8816 additions and 943 deletions
......@@ -33,4 +33,8 @@
# ide folder & virtual environments
.venv/
.vscode
\ No newline at end of file
.vscode
# rust specific
target
Cargo.lock
# mavlink_skyward_lib
Repo containing Skyward's implementation of the Mavlink protocol:
* `message_definitions` - XML files describing the available messages
* `mavlink_lib ` - corresponding C header files, generated with `pymavlink`
* `mavlink_rust` - Rust library of the Mavlink protocol
cd mavlink
python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/gemini.xml
python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
python3 -m pymavlink.tools.mavgen --lang=Python --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
\ No newline at end of file
This diff is collapsed.
This diff is collapsed.
......@@ -6,7 +6,7 @@
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_HASH 5773125515893874178
#define MAVLINK_PRIMARY_XML_HASH 1902963619411886953
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
......
......@@ -10,16 +10,20 @@ typedef struct __mavlink_adc_tm_t {
float channel_1; /*< [V] ADC voltage measured on channel 1*/
float channel_2; /*< [V] ADC voltage measured on channel 2*/
float channel_3; /*< [V] ADC voltage measured on channel 3*/
float channel_4; /*< [V] ADC voltage measured on channel 4*/
float channel_5; /*< [V] ADC voltage measured on channel 5*/
float channel_6; /*< [V] ADC voltage measured on channel 6*/
float channel_7; /*< [V] ADC voltage measured on channel 7*/
char sensor_name[20]; /*< Sensor name*/
} mavlink_adc_tm_t;
#define MAVLINK_MSG_ID_ADC_TM_LEN 44
#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 44
#define MAVLINK_MSG_ID_105_LEN 44
#define MAVLINK_MSG_ID_105_MIN_LEN 44
#define MAVLINK_MSG_ID_ADC_TM_LEN 60
#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 60
#define MAVLINK_MSG_ID_105_LEN 60
#define MAVLINK_MSG_ID_105_MIN_LEN 60
#define MAVLINK_MSG_ID_ADC_TM_CRC 223
#define MAVLINK_MSG_ID_105_CRC 223
#define MAVLINK_MSG_ID_ADC_TM_CRC 229
#define MAVLINK_MSG_ID_105_CRC 229
#define MAVLINK_MSG_ADC_TM_FIELD_SENSOR_NAME_LEN 20
......@@ -27,25 +31,33 @@ typedef struct __mavlink_adc_tm_t {
#define MAVLINK_MESSAGE_INFO_ADC_TM { \
105, \
"ADC_TM", \
6, \
10, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
{ "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 24, offsetof(mavlink_adc_tm_t, sensor_name) }, \
{ "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
{ "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
{ "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
{ "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
{ "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
{ "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
{ "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
{ "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
{ "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ADC_TM { \
"ADC_TM", \
6, \
10, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
{ "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 24, offsetof(mavlink_adc_tm_t, sensor_name) }, \
{ "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
{ "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
{ "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
{ "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
{ "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
{ "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
{ "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
{ "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
{ "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
} \
}
#endif
......@@ -62,10 +74,14 @@ typedef struct __mavlink_adc_tm_t {
* @param channel_1 [V] ADC voltage measured on channel 1
* @param channel_2 [V] ADC voltage measured on channel 2
* @param channel_3 [V] ADC voltage measured on channel 3
* @param channel_4 [V] ADC voltage measured on channel 4
* @param channel_5 [V] ADC voltage measured on channel 5
* @param channel_6 [V] ADC voltage measured on channel 6
* @param channel_7 [V] ADC voltage measured on channel 7
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3)
uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
......@@ -74,7 +90,11 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
_mav_put_float(buf, 12, channel_1);
_mav_put_float(buf, 16, channel_2);
_mav_put_float(buf, 20, channel_3);
_mav_put_char_array(buf, 24, sensor_name, 20);
_mav_put_float(buf, 24, channel_4);
_mav_put_float(buf, 28, channel_5);
_mav_put_float(buf, 32, channel_6);
_mav_put_float(buf, 36, channel_7);
_mav_put_char_array(buf, 40, sensor_name, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
#else
mavlink_adc_tm_t packet;
......@@ -83,6 +103,10 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
packet.channel_1 = channel_1;
packet.channel_2 = channel_2;
packet.channel_3 = channel_3;
packet.channel_4 = channel_4;
packet.channel_5 = channel_5;
packet.channel_6 = channel_6;
packet.channel_7 = channel_7;
mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
#endif
......@@ -103,11 +127,15 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon
* @param channel_1 [V] ADC voltage measured on channel 1
* @param channel_2 [V] ADC voltage measured on channel 2
* @param channel_3 [V] ADC voltage measured on channel 3
* @param channel_4 [V] ADC voltage measured on channel 4
* @param channel_5 [V] ADC voltage measured on channel 5
* @param channel_6 [V] ADC voltage measured on channel 6
* @param channel_7 [V] ADC voltage measured on channel 7
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t timestamp,const char *sensor_name,float channel_0,float channel_1,float channel_2,float channel_3)
uint64_t timestamp,const char *sensor_name,float channel_0,float channel_1,float channel_2,float channel_3,float channel_4,float channel_5,float channel_6,float channel_7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
......@@ -116,7 +144,11 @@ static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t c
_mav_put_float(buf, 12, channel_1);
_mav_put_float(buf, 16, channel_2);
_mav_put_float(buf, 20, channel_3);
_mav_put_char_array(buf, 24, sensor_name, 20);
_mav_put_float(buf, 24, channel_4);
_mav_put_float(buf, 28, channel_5);
_mav_put_float(buf, 32, channel_6);
_mav_put_float(buf, 36, channel_7);
_mav_put_char_array(buf, 40, sensor_name, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
#else
mavlink_adc_tm_t packet;
......@@ -125,6 +157,10 @@ static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t c
packet.channel_1 = channel_1;
packet.channel_2 = channel_2;
packet.channel_3 = channel_3;
packet.channel_4 = channel_4;
packet.channel_5 = channel_5;
packet.channel_6 = channel_6;
packet.channel_7 = channel_7;
mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
#endif
......@@ -143,7 +179,7 @@ static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t c
*/
static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
{
return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
}
/**
......@@ -157,7 +193,7 @@ static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t comp
*/
static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
{
return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
}
/**
......@@ -170,10 +206,14 @@ static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t
* @param channel_1 [V] ADC voltage measured on channel 1
* @param channel_2 [V] ADC voltage measured on channel 2
* @param channel_3 [V] ADC voltage measured on channel 3
* @param channel_4 [V] ADC voltage measured on channel 4
* @param channel_5 [V] ADC voltage measured on channel 5
* @param channel_6 [V] ADC voltage measured on channel 6
* @param channel_7 [V] ADC voltage measured on channel 7
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3)
static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
......@@ -182,7 +222,11 @@ static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t time
_mav_put_float(buf, 12, channel_1);
_mav_put_float(buf, 16, channel_2);
_mav_put_float(buf, 20, channel_3);
_mav_put_char_array(buf, 24, sensor_name, 20);
_mav_put_float(buf, 24, channel_4);
_mav_put_float(buf, 28, channel_5);
_mav_put_float(buf, 32, channel_6);
_mav_put_float(buf, 36, channel_7);
_mav_put_char_array(buf, 40, sensor_name, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
#else
mavlink_adc_tm_t packet;
......@@ -191,6 +235,10 @@ static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t time
packet.channel_1 = channel_1;
packet.channel_2 = channel_2;
packet.channel_3 = channel_3;
packet.channel_4 = channel_4;
packet.channel_5 = channel_5;
packet.channel_6 = channel_6;
packet.channel_7 = channel_7;
mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
#endif
......@@ -204,7 +252,7 @@ static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t time
static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
#endif
......@@ -218,7 +266,7 @@ static inline void mavlink_msg_adc_tm_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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3)
static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
......@@ -227,7 +275,11 @@ static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlin
_mav_put_float(buf, 12, channel_1);
_mav_put_float(buf, 16, channel_2);
_mav_put_float(buf, 20, channel_3);
_mav_put_char_array(buf, 24, sensor_name, 20);
_mav_put_float(buf, 24, channel_4);
_mav_put_float(buf, 28, channel_5);
_mav_put_float(buf, 32, channel_6);
_mav_put_float(buf, 36, channel_7);
_mav_put_char_array(buf, 40, sensor_name, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
#else
mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
......@@ -236,6 +288,10 @@ static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlin
packet->channel_1 = channel_1;
packet->channel_2 = channel_2;
packet->channel_3 = channel_3;
packet->channel_4 = channel_4;
packet->channel_5 = channel_5;
packet->channel_6 = channel_6;
packet->channel_7 = channel_7;
mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
#endif
......@@ -264,7 +320,7 @@ static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t*
*/
static inline uint16_t mavlink_msg_adc_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
{
return _MAV_RETURN_char_array(msg, sensor_name, 20, 24);
return _MAV_RETURN_char_array(msg, sensor_name, 20, 40);
}
/**
......@@ -307,6 +363,46 @@ static inline float mavlink_msg_adc_tm_get_channel_3(const mavlink_message_t* ms
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field channel_4 from adc_tm message
*
* @return [V] ADC voltage measured on channel 4
*/
static inline float mavlink_msg_adc_tm_get_channel_4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field channel_5 from adc_tm message
*
* @return [V] ADC voltage measured on channel 5
*/
static inline float mavlink_msg_adc_tm_get_channel_5(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field channel_6 from adc_tm message
*
* @return [V] ADC voltage measured on channel 6
*/
static inline float mavlink_msg_adc_tm_get_channel_6(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field channel_7 from adc_tm message
*
* @return [V] ADC voltage measured on channel 7
*/
static inline float mavlink_msg_adc_tm_get_channel_7(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Decode a adc_tm message into a struct
*
......@@ -321,6 +417,10 @@ static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavli
adc_tm->channel_1 = mavlink_msg_adc_tm_get_channel_1(msg);
adc_tm->channel_2 = mavlink_msg_adc_tm_get_channel_2(msg);
adc_tm->channel_3 = mavlink_msg_adc_tm_get_channel_3(msg);
adc_tm->channel_4 = mavlink_msg_adc_tm_get_channel_4(msg);
adc_tm->channel_5 = mavlink_msg_adc_tm_get_channel_5(msg);
adc_tm->channel_6 = mavlink_msg_adc_tm_get_channel_6(msg);
adc_tm->channel_7 = mavlink_msg_adc_tm_get_channel_7(msg);
mavlink_msg_adc_tm_get_sensor_name(msg, adc_tm->sensor_name);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
......
This diff is collapsed.
#pragma once
// MESSAGE MEA_TM PACKING
#define MAVLINK_MSG_ID_MEA_TM 207
typedef struct __mavlink_mea_tm_t {
uint64_t timestamp; /*< [us] When was this logged*/
float kalman_x0; /*< Kalman state variable 0 (corrected pressure)*/
float kalman_x1; /*< Kalman state variable 1 */
float kalman_x2; /*< Kalman state variable 2 (mass)*/
float mass; /*< [kg] Mass estimated*/
float corrected_pressure; /*< [kg] Corrected pressure*/
uint8_t state; /*< MEA current state*/
} mavlink_mea_tm_t;
#define MAVLINK_MSG_ID_MEA_TM_LEN 29
#define MAVLINK_MSG_ID_MEA_TM_MIN_LEN 29
#define MAVLINK_MSG_ID_207_LEN 29
#define MAVLINK_MSG_ID_207_MIN_LEN 29
#define MAVLINK_MSG_ID_MEA_TM_CRC 11
#define MAVLINK_MSG_ID_207_CRC 11
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MEA_TM { \
207, \
"MEA_TM", \
7, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \
{ "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \
{ "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \
{ "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \
{ "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \
{ "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \
{ "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MEA_TM { \
"MEA_TM", \
7, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \
{ "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \
{ "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \
{ "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \
{ "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \
{ "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \
{ "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \
} \
}
#endif
/**
* @brief Pack a mea_tm message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param timestamp [us] When was this logged
* @param state MEA current state
* @param kalman_x0 Kalman state variable 0 (corrected pressure)
* @param kalman_x1 Kalman state variable 1
* @param kalman_x2 Kalman state variable 2 (mass)
* @param mass [kg] Mass estimated
* @param corrected_pressure [kg] Corrected pressure
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, kalman_x0);
_mav_put_float(buf, 12, kalman_x1);
_mav_put_float(buf, 16, kalman_x2);
_mav_put_float(buf, 20, mass);
_mav_put_float(buf, 24, corrected_pressure);
_mav_put_uint8_t(buf, 28, state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
#else
mavlink_mea_tm_t packet;
packet.timestamp = timestamp;
packet.kalman_x0 = kalman_x0;
packet.kalman_x1 = kalman_x1;
packet.kalman_x2 = kalman_x2;
packet.mass = mass;
packet.corrected_pressure = corrected_pressure;
packet.state = state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MEA_TM;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
}
/**
* @brief Pack a mea_tm message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param timestamp [us] When was this logged
* @param state MEA current state
* @param kalman_x0 Kalman state variable 0 (corrected pressure)
* @param kalman_x1 Kalman state variable 1
* @param kalman_x2 Kalman state variable 2 (mass)
* @param mass [kg] Mass estimated
* @param corrected_pressure [kg] Corrected pressure
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mea_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float mass,float corrected_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, kalman_x0);
_mav_put_float(buf, 12, kalman_x1);
_mav_put_float(buf, 16, kalman_x2);
_mav_put_float(buf, 20, mass);
_mav_put_float(buf, 24, corrected_pressure);
_mav_put_uint8_t(buf, 28, state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
#else
mavlink_mea_tm_t packet;
packet.timestamp = timestamp;
packet.kalman_x0 = kalman_x0;
packet.kalman_x1 = kalman_x1;
packet.kalman_x2 = kalman_x2;
packet.mass = mass;
packet.corrected_pressure = corrected_pressure;
packet.state = state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MEA_TM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
}
/**
* @brief Encode a mea_tm struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mea_tm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mea_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
{
return mavlink_msg_mea_tm_pack(system_id, component_id, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
}
/**
* @brief Encode a mea_tm struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param mea_tm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mea_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
{
return mavlink_msg_mea_tm_pack_chan(system_id, component_id, chan, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
}
/**
* @brief Send a mea_tm message
* @param chan MAVLink channel to send the message
*
* @param timestamp [us] When was this logged
* @param state MEA current state
* @param kalman_x0 Kalman state variable 0 (corrected pressure)
* @param kalman_x1 Kalman state variable 1
* @param kalman_x2 Kalman state variable 2 (mass)
* @param mass [kg] Mass estimated
* @param corrected_pressure [kg] Corrected pressure
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mea_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, kalman_x0);
_mav_put_float(buf, 12, kalman_x1);
_mav_put_float(buf, 16, kalman_x2);
_mav_put_float(buf, 20, mass);
_mav_put_float(buf, 24, corrected_pressure);
_mav_put_uint8_t(buf, 28, state);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
#else
mavlink_mea_tm_t packet;
packet.timestamp = timestamp;
packet.kalman_x0 = kalman_x0;
packet.kalman_x1 = kalman_x1;
packet.kalman_x2 = kalman_x2;
packet.mass = mass;
packet.corrected_pressure = corrected_pressure;
packet.state = state;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)&packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
#endif
}
/**
* @brief Send a mea_tm message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mea_tm_send_struct(mavlink_channel_t chan, const mavlink_mea_tm_t* mea_tm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mea_tm_send(chan, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)mea_tm, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
#endif
}
#if MAVLINK_MSG_ID_MEA_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
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_mea_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, kalman_x0);
_mav_put_float(buf, 12, kalman_x1);
_mav_put_float(buf, 16, kalman_x2);
_mav_put_float(buf, 20, mass);
_mav_put_float(buf, 24, corrected_pressure);
_mav_put_uint8_t(buf, 28, state);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
#else
mavlink_mea_tm_t *packet = (mavlink_mea_tm_t *)msgbuf;
packet->timestamp = timestamp;
packet->kalman_x0 = kalman_x0;
packet->kalman_x1 = kalman_x1;
packet->kalman_x2 = kalman_x2;
packet->mass = mass;
packet->corrected_pressure = corrected_pressure;
packet->state = state;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
#endif
}
#endif
#endif
// MESSAGE MEA_TM UNPACKING
/**
* @brief Get field timestamp from mea_tm message
*
* @return [us] When was this logged
*/
static inline uint64_t mavlink_msg_mea_tm_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field state from mea_tm message
*
* @return MEA current state
*/
static inline uint8_t mavlink_msg_mea_tm_get_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
/**
* @brief Get field kalman_x0 from mea_tm message
*
* @return Kalman state variable 0 (corrected pressure)
*/
static inline float mavlink_msg_mea_tm_get_kalman_x0(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field kalman_x1 from mea_tm message
*
* @return Kalman state variable 1
*/
static inline float mavlink_msg_mea_tm_get_kalman_x1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field kalman_x2 from mea_tm message
*
* @return Kalman state variable 2 (mass)
*/
static inline float mavlink_msg_mea_tm_get_kalman_x2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field mass from mea_tm message
*
* @return [kg] Mass estimated
*/
static inline float mavlink_msg_mea_tm_get_mass(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field corrected_pressure from mea_tm message
*
* @return [kg] Corrected pressure
*/
static inline float mavlink_msg_mea_tm_get_corrected_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a mea_tm message into a struct
*
* @param msg The message to decode
* @param mea_tm C-struct to decode the message contents into
*/
static inline void mavlink_msg_mea_tm_decode(const mavlink_message_t* msg, mavlink_mea_tm_t* mea_tm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mea_tm->timestamp = mavlink_msg_mea_tm_get_timestamp(msg);
mea_tm->kalman_x0 = mavlink_msg_mea_tm_get_kalman_x0(msg);
mea_tm->kalman_x1 = mavlink_msg_mea_tm_get_kalman_x1(msg);
mea_tm->kalman_x2 = mavlink_msg_mea_tm_get_kalman_x2(msg);
mea_tm->mass = mavlink_msg_mea_tm_get_mass(msg);
mea_tm->corrected_pressure = mavlink_msg_mea_tm_get_corrected_pressure(msg);
mea_tm->state = mavlink_msg_mea_tm_get_state(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MEA_TM_LEN? msg->len : MAVLINK_MSG_ID_MEA_TM_LEN;
memset(mea_tm, 0, MAVLINK_MSG_ID_MEA_TM_LEN);
memcpy(mea_tm, _MAV_PAYLOAD(msg), len);
#endif
}
......@@ -5,7 +5,7 @@
typedef struct __mavlink_set_servo_angle_tc_t {
float angle; /*< [deg] Servo angle*/
float angle; /*< Servo angle in normalized value [0-1]*/
uint8_t servo_id; /*< A member of the ServosList enum*/
} mavlink_set_servo_angle_tc_t;
......@@ -45,7 +45,7 @@ typedef struct __mavlink_set_servo_angle_tc_t {
* @param msg The MAVLink message to compress the data into
*
* @param servo_id A member of the ServosList enum
* @param angle [deg] Servo angle
* @param angle Servo angle in normalized value [0-1]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
......@@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, ui
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param servo_id A member of the ServosList enum
* @param angle [deg] Servo angle
* @param angle Servo angle in normalized value [0-1]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_servo_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
......@@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_chan(uint8_t system
* @param chan MAVLink channel to send the message
*
* @param servo_id A member of the ServosList enum
* @param angle [deg] Servo angle
* @param angle Servo angle in normalized value [0-1]
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
......@@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_set_servo_angle_tc_get_servo_id(const mavlink_
/**
* @brief Get field angle from set_servo_angle_tc message
*
* @return [deg] Servo angle
* @return Servo angle in normalized value [0-1]
*/
static inline float mavlink_msg_set_servo_angle_tc_get_angle(const mavlink_message_t* msg)
{
......
This diff is collapsed.
......@@ -7,8 +7,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Apr 21 2023"
#define MAVLINK_BUILD_DATE "Wed Sep 13 2023"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 171
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176
#endif // MAVLINK_VERSION_H
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.