|
|
|
@ -5,11 +5,12 @@
@@ -5,11 +5,12 @@
|
|
|
|
|
typedef struct __mavlink_radio_t |
|
|
|
|
{ |
|
|
|
|
uint16_t rxerrors; ///< receive errors
|
|
|
|
|
uint16_t serrors; ///< serial errors
|
|
|
|
|
uint16_t fixed; ///< count of error corrected packets
|
|
|
|
|
uint8_t rssi; ///< local signal strength
|
|
|
|
|
uint8_t remrssi; ///< remote signal strength
|
|
|
|
|
uint8_t txbuf; ///< how full the tx buffer is as a percentage
|
|
|
|
|
uint8_t noise; ///< background noise level
|
|
|
|
|
uint8_t remnoise; ///< remote background noise level
|
|
|
|
|
} mavlink_radio_t; |
|
|
|
|
|
|
|
|
|
#define MAVLINK_MSG_ID_RADIO_LEN 9 |
|
|
|
@ -19,13 +20,14 @@ typedef struct __mavlink_radio_t
@@ -19,13 +20,14 @@ typedef struct __mavlink_radio_t
|
|
|
|
|
|
|
|
|
|
#define MAVLINK_MESSAGE_INFO_RADIO { \ |
|
|
|
|
"RADIO", \
|
|
|
|
|
6, \
|
|
|
|
|
7, \
|
|
|
|
|
{ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
|
|
|
|
|
{ "serrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, serrors) }, \
|
|
|
|
|
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_radio_t, fixed) }, \
|
|
|
|
|
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, rssi) }, \
|
|
|
|
|
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, remrssi) }, \
|
|
|
|
|
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, txbuf) }, \
|
|
|
|
|
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
|
|
|
|
|
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
|
|
|
|
|
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
|
|
|
|
|
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
|
|
|
|
|
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
|
|
|
|
|
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
|
|
|
|
|
} \
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -39,38 +41,41 @@ typedef struct __mavlink_radio_t
@@ -39,38 +41,41 @@ typedef struct __mavlink_radio_t
|
|
|
|
|
* @param rssi local signal strength |
|
|
|
|
* @param remrssi remote signal strength |
|
|
|
|
* @param txbuf how full the tx buffer is as a percentage |
|
|
|
|
* @param noise background noise level |
|
|
|
|
* @param remnoise remote background noise level |
|
|
|
|
* @param rxerrors receive errors |
|
|
|
|
* @param serrors serial errors |
|
|
|
|
* @param fixed count of error corrected packets |
|
|
|
|
* @return length of the message in bytes (excluding serial stream start sign) |
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
|
|
|
|
uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed) |
|
|
|
|
uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) |
|
|
|
|
{ |
|
|
|
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
|
|
|
|
char buf[9]; |
|
|
|
|
_mav_put_uint16_t(buf, 0, rxerrors); |
|
|
|
|
_mav_put_uint16_t(buf, 2, serrors); |
|
|
|
|
_mav_put_uint16_t(buf, 4, fixed); |
|
|
|
|
_mav_put_uint8_t(buf, 6, rssi); |
|
|
|
|
_mav_put_uint8_t(buf, 7, remrssi); |
|
|
|
|
_mav_put_uint8_t(buf, 8, txbuf); |
|
|
|
|
_mav_put_uint16_t(buf, 2, fixed); |
|
|
|
|
_mav_put_uint8_t(buf, 4, rssi); |
|
|
|
|
_mav_put_uint8_t(buf, 5, remrssi); |
|
|
|
|
_mav_put_uint8_t(buf, 6, txbuf); |
|
|
|
|
_mav_put_uint8_t(buf, 7, noise); |
|
|
|
|
_mav_put_uint8_t(buf, 8, remnoise); |
|
|
|
|
|
|
|
|
|
memcpy(_MAV_PAYLOAD(msg), buf, 9); |
|
|
|
|
#else |
|
|
|
|
mavlink_radio_t packet; |
|
|
|
|
packet.rxerrors = rxerrors; |
|
|
|
|
packet.serrors = serrors; |
|
|
|
|
packet.fixed = fixed; |
|
|
|
|
packet.rssi = rssi; |
|
|
|
|
packet.remrssi = remrssi; |
|
|
|
|
packet.txbuf = txbuf; |
|
|
|
|
packet.noise = noise; |
|
|
|
|
packet.remnoise = remnoise; |
|
|
|
|
|
|
|
|
|
memcpy(_MAV_PAYLOAD(msg), &packet, 9); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
msg->msgid = MAVLINK_MSG_ID_RADIO; |
|
|
|
|
return mavlink_finalize_message(msg, system_id, component_id, 9, 244); |
|
|
|
|
return mavlink_finalize_message(msg, system_id, component_id, 9, 21); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -82,39 +87,42 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
@@ -82,39 +87,42 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
|
|
|
|
|
* @param rssi local signal strength |
|
|
|
|
* @param remrssi remote signal strength |
|
|
|
|
* @param txbuf how full the tx buffer is as a percentage |
|
|
|
|
* @param noise background noise level |
|
|
|
|
* @param remnoise remote background noise level |
|
|
|
|
* @param rxerrors receive errors |
|
|
|
|
* @param serrors serial errors |
|
|
|
|
* @param fixed count of error corrected packets |
|
|
|
|
* @return length of the message in bytes (excluding serial stream start sign) |
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
|
|
|
|
mavlink_message_t* msg, |
|
|
|
|
uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint16_t rxerrors,uint16_t serrors,uint16_t fixed) |
|
|
|
|
uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) |
|
|
|
|
{ |
|
|
|
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
|
|
|
|
char buf[9]; |
|
|
|
|
_mav_put_uint16_t(buf, 0, rxerrors); |
|
|
|
|
_mav_put_uint16_t(buf, 2, serrors); |
|
|
|
|
_mav_put_uint16_t(buf, 4, fixed); |
|
|
|
|
_mav_put_uint8_t(buf, 6, rssi); |
|
|
|
|
_mav_put_uint8_t(buf, 7, remrssi); |
|
|
|
|
_mav_put_uint8_t(buf, 8, txbuf); |
|
|
|
|
_mav_put_uint16_t(buf, 2, fixed); |
|
|
|
|
_mav_put_uint8_t(buf, 4, rssi); |
|
|
|
|
_mav_put_uint8_t(buf, 5, remrssi); |
|
|
|
|
_mav_put_uint8_t(buf, 6, txbuf); |
|
|
|
|
_mav_put_uint8_t(buf, 7, noise); |
|
|
|
|
_mav_put_uint8_t(buf, 8, remnoise); |
|
|
|
|
|
|
|
|
|
memcpy(_MAV_PAYLOAD(msg), buf, 9); |
|
|
|
|
#else |
|
|
|
|
mavlink_radio_t packet; |
|
|
|
|
packet.rxerrors = rxerrors; |
|
|
|
|
packet.serrors = serrors; |
|
|
|
|
packet.fixed = fixed; |
|
|
|
|
packet.rssi = rssi; |
|
|
|
|
packet.remrssi = remrssi; |
|
|
|
|
packet.txbuf = txbuf; |
|
|
|
|
packet.noise = noise; |
|
|
|
|
packet.remnoise = remnoise; |
|
|
|
|
|
|
|
|
|
memcpy(_MAV_PAYLOAD(msg), &packet, 9); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
msg->msgid = MAVLINK_MSG_ID_RADIO; |
|
|
|
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 244); |
|
|
|
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 21); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -127,7 +135,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
@@ -127,7 +135,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
|
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio) |
|
|
|
|
{ |
|
|
|
|
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->rxerrors, radio->serrors, radio->fixed); |
|
|
|
|
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -137,34 +145,37 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo
@@ -137,34 +145,37 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo
|
|
|
|
|
* @param rssi local signal strength |
|
|
|
|
* @param remrssi remote signal strength |
|
|
|
|
* @param txbuf how full the tx buffer is as a percentage |
|
|
|
|
* @param noise background noise level |
|
|
|
|
* @param remnoise remote background noise level |
|
|
|
|
* @param rxerrors receive errors |
|
|
|
|
* @param serrors serial errors |
|
|
|
|
* @param fixed count of error corrected packets |
|
|
|
|
*/ |
|
|
|
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
|
|
|
|
|
|
|
|
|
static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed) |
|
|
|
|
static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) |
|
|
|
|
{ |
|
|
|
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
|
|
|
|
char buf[9]; |
|
|
|
|
_mav_put_uint16_t(buf, 0, rxerrors); |
|
|
|
|
_mav_put_uint16_t(buf, 2, serrors); |
|
|
|
|
_mav_put_uint16_t(buf, 4, fixed); |
|
|
|
|
_mav_put_uint8_t(buf, 6, rssi); |
|
|
|
|
_mav_put_uint8_t(buf, 7, remrssi); |
|
|
|
|
_mav_put_uint8_t(buf, 8, txbuf); |
|
|
|
|
_mav_put_uint16_t(buf, 2, fixed); |
|
|
|
|
_mav_put_uint8_t(buf, 4, rssi); |
|
|
|
|
_mav_put_uint8_t(buf, 5, remrssi); |
|
|
|
|
_mav_put_uint8_t(buf, 6, txbuf); |
|
|
|
|
_mav_put_uint8_t(buf, 7, noise); |
|
|
|
|
_mav_put_uint8_t(buf, 8, remnoise); |
|
|
|
|
|
|
|
|
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 244); |
|
|
|
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 21); |
|
|
|
|
#else |
|
|
|
|
mavlink_radio_t packet; |
|
|
|
|
packet.rxerrors = rxerrors; |
|
|
|
|
packet.serrors = serrors; |
|
|
|
|
packet.fixed = fixed; |
|
|
|
|
packet.rssi = rssi; |
|
|
|
|
packet.remrssi = remrssi; |
|
|
|
|
packet.txbuf = txbuf; |
|
|
|
|
packet.noise = noise; |
|
|
|
|
packet.remnoise = remnoise; |
|
|
|
|
|
|
|
|
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 244); |
|
|
|
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 21); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -180,7 +191,7 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi,
@@ -180,7 +191,7 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi,
|
|
|
|
|
*/ |
|
|
|
|
static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 6); |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 4); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -190,7 +201,7 @@ static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
@@ -190,7 +201,7 @@ static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
|
|
|
|
|
*/ |
|
|
|
|
static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 7); |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 5); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -200,27 +211,37 @@ static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg
@@ -200,27 +211,37 @@ static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg
|
|
|
|
|
*/ |
|
|
|
|
static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 8); |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 6); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Get field rxerrors from radio message |
|
|
|
|
* @brief Get field noise from radio message |
|
|
|
|
* |
|
|
|
|
* @return receive errors |
|
|
|
|
* @return background noise level |
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg) |
|
|
|
|
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint16_t(msg, 0); |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 7); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Get field serrors from radio message |
|
|
|
|
* @brief Get field remnoise from radio message |
|
|
|
|
* |
|
|
|
|
* @return serial errors |
|
|
|
|
* @return remote background noise level |
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* msg) |
|
|
|
|
static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint16_t(msg, 2); |
|
|
|
|
return _MAV_RETURN_uint8_t(msg, 8); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Get field rxerrors from radio message |
|
|
|
|
* |
|
|
|
|
* @return receive errors |
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint16_t(msg, 0); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -230,7 +251,7 @@ static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* ms
@@ -230,7 +251,7 @@ static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* ms
|
|
|
|
|
*/ |
|
|
|
|
static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg) |
|
|
|
|
{ |
|
|
|
|
return _MAV_RETURN_uint16_t(msg, 4); |
|
|
|
|
return _MAV_RETURN_uint16_t(msg, 2); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -243,11 +264,12 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
@@ -243,11 +264,12 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
|
|
|
|
|
{ |
|
|
|
|
#if MAVLINK_NEED_BYTE_SWAP |
|
|
|
|
radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg); |
|
|
|
|
radio->serrors = mavlink_msg_radio_get_serrors(msg); |
|
|
|
|
radio->fixed = mavlink_msg_radio_get_fixed(msg); |
|
|
|
|
radio->rssi = mavlink_msg_radio_get_rssi(msg); |
|
|
|
|
radio->remrssi = mavlink_msg_radio_get_remrssi(msg); |
|
|
|
|
radio->txbuf = mavlink_msg_radio_get_txbuf(msg); |
|
|
|
|
radio->noise = mavlink_msg_radio_get_noise(msg); |
|
|
|
|
radio->remnoise = mavlink_msg_radio_get_remnoise(msg); |
|
|
|
|
#else |
|
|
|
|
memcpy(radio, _MAV_PAYLOAD(msg), 9); |
|
|
|
|
#endif |
|
|
|
|