diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
index d86853ff9e..72ebba618d 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
@@ -12,11 +12,11 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
+#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 213, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
+#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
#endif
#ifndef MAVLINK_MESSAGE_INFO
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
index 65d04a7f13..1a40398201 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
@@ -6,14 +6,14 @@ typedef struct __mavlink_radio_t
{
uint8_t rssi; ///< local signal strength
uint8_t remrssi; ///< remote signal strength
+ uint8_t txbuf; ///< how full the tx buffer is as a percentage
uint16_t rxerrors; ///< receive errors
uint16_t serrors; ///< serial errors
uint16_t fixed; ///< count of error corrected packets
- uint16_t txbuf; ///< number of bytes available in transmit buffer
} mavlink_radio_t;
-#define MAVLINK_MSG_ID_RADIO_LEN 10
-#define MAVLINK_MSG_ID_166_LEN 10
+#define MAVLINK_MSG_ID_RADIO_LEN 9
+#define MAVLINK_MSG_ID_166_LEN 9
@@ -22,10 +22,10 @@ typedef struct __mavlink_radio_t
6, \
{ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_radio_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_radio_t, remrssi) }, \
- { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, rxerrors) }, \
- { "serrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_radio_t, serrors) }, \
- { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_radio_t, fixed) }, \
- { "txbuf", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_radio_t, txbuf) }, \
+ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_radio_t, txbuf) }, \
+ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_radio_t, rxerrors) }, \
+ { "serrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, serrors) }, \
+ { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \
} \
}
@@ -38,39 +38,39 @@ 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 rxerrors receive errors
* @param serrors serial errors
* @param fixed count of error corrected packets
- * @param txbuf number of bytes available in transmit buffer
* @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, uint16_t rxerrors, uint16_t serrors, uint16_t fixed, uint16_t txbuf)
+ uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[10];
+ char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
- _mav_put_uint16_t(buf, 2, rxerrors);
- _mav_put_uint16_t(buf, 4, serrors);
- _mav_put_uint16_t(buf, 6, fixed);
- _mav_put_uint16_t(buf, 8, txbuf);
+ _mav_put_uint8_t(buf, 2, txbuf);
+ _mav_put_uint16_t(buf, 3, rxerrors);
+ _mav_put_uint16_t(buf, 5, serrors);
+ _mav_put_uint16_t(buf, 7, fixed);
- memcpy(_MAV_PAYLOAD(msg), buf, 10);
+ memcpy(_MAV_PAYLOAD(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
packet.rxerrors = rxerrors;
packet.serrors = serrors;
packet.fixed = fixed;
- packet.txbuf = txbuf;
- memcpy(_MAV_PAYLOAD(msg), &packet, 10);
+ memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
- return mavlink_finalize_message(msg, system_id, component_id, 10);
+ return mavlink_finalize_message(msg, system_id, component_id, 9);
}
/**
@@ -81,40 +81,40 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
+ * @param txbuf how full the tx buffer is as a percentage
* @param rxerrors receive errors
* @param serrors serial errors
* @param fixed count of error corrected packets
- * @param txbuf number of bytes available in transmit buffer
* @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,uint16_t rxerrors,uint16_t serrors,uint16_t fixed,uint16_t txbuf)
+ uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint16_t rxerrors,uint16_t serrors,uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[10];
+ char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
- _mav_put_uint16_t(buf, 2, rxerrors);
- _mav_put_uint16_t(buf, 4, serrors);
- _mav_put_uint16_t(buf, 6, fixed);
- _mav_put_uint16_t(buf, 8, txbuf);
+ _mav_put_uint8_t(buf, 2, txbuf);
+ _mav_put_uint16_t(buf, 3, rxerrors);
+ _mav_put_uint16_t(buf, 5, serrors);
+ _mav_put_uint16_t(buf, 7, fixed);
- memcpy(_MAV_PAYLOAD(msg), buf, 10);
+ memcpy(_MAV_PAYLOAD(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
packet.rxerrors = rxerrors;
packet.serrors = serrors;
packet.fixed = fixed;
- packet.txbuf = txbuf;
- memcpy(_MAV_PAYLOAD(msg), &packet, 10);
+ memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 10);
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9);
}
/**
@@ -127,7 +127,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->rxerrors, radio->serrors, radio->fixed, radio->txbuf);
+ return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->rxerrors, radio->serrors, radio->fixed);
}
/**
@@ -136,35 +136,35 @@ 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 rxerrors receive errors
* @param serrors serial errors
* @param fixed count of error corrected packets
- * @param txbuf number of bytes available in transmit buffer
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint16_t rxerrors, uint16_t serrors, uint16_t fixed, uint16_t txbuf)
+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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[10];
+ char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
- _mav_put_uint16_t(buf, 2, rxerrors);
- _mav_put_uint16_t(buf, 4, serrors);
- _mav_put_uint16_t(buf, 6, fixed);
- _mav_put_uint16_t(buf, 8, txbuf);
+ _mav_put_uint8_t(buf, 2, txbuf);
+ _mav_put_uint16_t(buf, 3, rxerrors);
+ _mav_put_uint16_t(buf, 5, serrors);
+ _mav_put_uint16_t(buf, 7, fixed);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 10);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
packet.rxerrors = rxerrors;
packet.serrors = serrors;
packet.fixed = fixed;
- packet.txbuf = txbuf;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 10);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9);
#endif
}
@@ -193,6 +193,16 @@ static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg
return _MAV_RETURN_uint8_t(msg, 1);
}
+/**
+ * @brief Get field txbuf from radio message
+ *
+ * @return how full the tx buffer is as a percentage
+ */
+static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
/**
* @brief Get field rxerrors from radio message
*
@@ -200,7 +210,7 @@ static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg
*/
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
{
- return _MAV_RETURN_uint16_t(msg, 2);
+ return _MAV_RETURN_uint16_t(msg, 3);
}
/**
@@ -210,7 +220,7 @@ static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* m
*/
static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* msg)
{
- return _MAV_RETURN_uint16_t(msg, 4);
+ return _MAV_RETURN_uint16_t(msg, 5);
}
/**
@@ -220,17 +230,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, 6);
-}
-
-/**
- * @brief Get field txbuf from radio message
- *
- * @return number of bytes available in transmit buffer
- */
-static inline uint16_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 8);
+ return _MAV_RETURN_uint16_t(msg, 7);
}
/**
@@ -244,11 +244,11 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
#if MAVLINK_NEED_BYTE_SWAP
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->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
radio->serrors = mavlink_msg_radio_get_serrors(msg);
radio->fixed = mavlink_msg_radio_get_fixed(msg);
- radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
#else
- memcpy(radio, _MAV_PAYLOAD(msg), 10);
+ memcpy(radio, _MAV_PAYLOAD(msg), 9);
#endif
}
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
index 2e8fa205ab..d35e81bd4b 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
@@ -835,19 +835,19 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
mavlink_radio_t packet_in = {
5,
72,
- 17339,
- 17443,
- 17547,
- 17651,
+ 139,
+ 17391,
+ 17495,
+ 17599,
};
mavlink_radio_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.rssi = packet_in.rssi;
packet1.remrssi = packet_in.remrssi;
+ packet1.txbuf = packet_in.txbuf;
packet1.rxerrors = packet_in.rxerrors;
packet1.serrors = packet_in.serrors;
packet1.fixed = packet_in.fixed;
- packet1.txbuf = packet_in.txbuf;
@@ -857,12 +857,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.rxerrors , packet1.serrors , packet1.fixed , packet1.txbuf );
+ mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.rxerrors , packet1.serrors , packet1.fixed , packet1.txbuf );
+ mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@@ -875,7 +875,7 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.rxerrors , packet1.serrors , packet1.fixed , packet1.txbuf );
+ mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
mavlink_msg_radio_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/ardupilotmega/version.h
index e75b32754a..78e9d02f51 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/version.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Sun Apr 1 16:31:09 2012"
+#define MAVLINK_BUILD_DATE "Mon Apr 2 09:57:26 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
diff --git a/libraries/GCS_MAVLink/include/common/version.h b/libraries/GCS_MAVLink/include/common/version.h
index 805e2fe808..edc521ae72 100644
--- a/libraries/GCS_MAVLink/include/common/version.h
+++ b/libraries/GCS_MAVLink/include/common/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Sun Apr 1 16:31:09 2012"
+#define MAVLINK_BUILD_DATE "Mon Apr 2 09:57:26 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
index 176d96a487..0d168ba758 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
@@ -12,11 +12,11 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 128, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 244, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
#endif
#ifndef MAVLINK_MESSAGE_INFO
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h
index bc11035645..546daddd1d 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h
@@ -7,13 +7,13 @@ typedef struct __mavlink_radio_t
uint16_t rxerrors; ///< receive errors
uint16_t serrors; ///< serial errors
uint16_t fixed; ///< count of error corrected packets
- uint16_t txbuf; ///< number of bytes available in transmit buffer
uint8_t rssi; ///< local signal strength
uint8_t remrssi; ///< remote signal strength
+ uint8_t txbuf; ///< how full the tx buffer is as a percentage
} mavlink_radio_t;
-#define MAVLINK_MSG_ID_RADIO_LEN 10
-#define MAVLINK_MSG_ID_166_LEN 10
+#define MAVLINK_MSG_ID_RADIO_LEN 9
+#define MAVLINK_MSG_ID_166_LEN 9
@@ -23,9 +23,9 @@ typedef struct __mavlink_radio_t
{ { "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) }, \
- { "txbuf", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
- { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, rssi) }, \
- { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_radio_t, remrssi) }, \
+ { "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) }, \
} \
}
@@ -38,39 +38,39 @@ 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 rxerrors receive errors
* @param serrors serial errors
* @param fixed count of error corrected packets
- * @param txbuf number of bytes available in transmit buffer
* @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, uint16_t rxerrors, uint16_t serrors, uint16_t fixed, uint16_t txbuf)
+ uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[10];
+ 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_uint16_t(buf, 6, txbuf);
- _mav_put_uint8_t(buf, 8, rssi);
- _mav_put_uint8_t(buf, 9, remrssi);
+ _mav_put_uint8_t(buf, 6, rssi);
+ _mav_put_uint8_t(buf, 7, remrssi);
+ _mav_put_uint8_t(buf, 8, txbuf);
- memcpy(_MAV_PAYLOAD(msg), buf, 10);
+ memcpy(_MAV_PAYLOAD(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.serrors = serrors;
packet.fixed = fixed;
- packet.txbuf = txbuf;
packet.rssi = rssi;
packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
- memcpy(_MAV_PAYLOAD(msg), &packet, 10);
+ memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
- return mavlink_finalize_message(msg, system_id, component_id, 10, 128);
+ return mavlink_finalize_message(msg, system_id, component_id, 9, 244);
}
/**
@@ -81,40 +81,40 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
+ * @param txbuf how full the tx buffer is as a percentage
* @param rxerrors receive errors
* @param serrors serial errors
* @param fixed count of error corrected packets
- * @param txbuf number of bytes available in transmit buffer
* @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,uint16_t rxerrors,uint16_t serrors,uint16_t fixed,uint16_t txbuf)
+ uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint16_t rxerrors,uint16_t serrors,uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[10];
+ 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_uint16_t(buf, 6, txbuf);
- _mav_put_uint8_t(buf, 8, rssi);
- _mav_put_uint8_t(buf, 9, remrssi);
+ _mav_put_uint8_t(buf, 6, rssi);
+ _mav_put_uint8_t(buf, 7, remrssi);
+ _mav_put_uint8_t(buf, 8, txbuf);
- memcpy(_MAV_PAYLOAD(msg), buf, 10);
+ memcpy(_MAV_PAYLOAD(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.serrors = serrors;
packet.fixed = fixed;
- packet.txbuf = txbuf;
packet.rssi = rssi;
packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
- memcpy(_MAV_PAYLOAD(msg), &packet, 10);
+ memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 10, 128);
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 244);
}
/**
@@ -127,7 +127,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->rxerrors, radio->serrors, radio->fixed, radio->txbuf);
+ return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->rxerrors, radio->serrors, radio->fixed);
}
/**
@@ -136,35 +136,35 @@ 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 rxerrors receive errors
* @param serrors serial errors
* @param fixed count of error corrected packets
- * @param txbuf number of bytes available in transmit buffer
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint16_t rxerrors, uint16_t serrors, uint16_t fixed, uint16_t txbuf)
+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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[10];
+ 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_uint16_t(buf, 6, txbuf);
- _mav_put_uint8_t(buf, 8, rssi);
- _mav_put_uint8_t(buf, 9, remrssi);
+ _mav_put_uint8_t(buf, 6, rssi);
+ _mav_put_uint8_t(buf, 7, remrssi);
+ _mav_put_uint8_t(buf, 8, txbuf);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 10, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 244);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.serrors = serrors;
packet.fixed = fixed;
- packet.txbuf = txbuf;
packet.rssi = rssi;
packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 10, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 244);
#endif
}
@@ -180,7 +180,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, 8);
+ return _MAV_RETURN_uint8_t(msg, 6);
}
/**
@@ -190,7 +190,17 @@ 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, 9);
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field txbuf from radio message
+ *
+ * @return how full the tx buffer is as a percentage
+ */
+static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
}
/**
@@ -223,16 +233,6 @@ static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
return _MAV_RETURN_uint16_t(msg, 4);
}
-/**
- * @brief Get field txbuf from radio message
- *
- * @return number of bytes available in transmit buffer
- */
-static inline uint16_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 6);
-}
-
/**
* @brief Decode a radio message into a struct
*
@@ -245,10 +245,10 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
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->txbuf = mavlink_msg_radio_get_txbuf(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);
#else
- memcpy(radio, _MAV_PAYLOAD(msg), 10);
+ memcpy(radio, _MAV_PAYLOAD(msg), 9);
#endif
}
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
index 14c0a78b34..12f9aad722 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
@@ -836,18 +836,18 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
17235,
17339,
17443,
- 17547,
+ 151,
+ 218,
29,
- 96,
};
mavlink_radio_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.rxerrors = packet_in.rxerrors;
packet1.serrors = packet_in.serrors;
packet1.fixed = packet_in.fixed;
- packet1.txbuf = packet_in.txbuf;
packet1.rssi = packet_in.rssi;
packet1.remrssi = packet_in.remrssi;
+ packet1.txbuf = packet_in.txbuf;
@@ -857,12 +857,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.rxerrors , packet1.serrors , packet1.fixed , packet1.txbuf );
+ mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.rxerrors , packet1.serrors , packet1.fixed , packet1.txbuf );
+ mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@@ -875,7 +875,7 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.rxerrors , packet1.serrors , packet1.fixed , packet1.txbuf );
+ mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
mavlink_msg_radio_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
index c49f950845..979dcb6367 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Sun Apr 1 16:31:09 2012"
+#define MAVLINK_BUILD_DATE "Mon Apr 2 09:57:26 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
diff --git a/libraries/GCS_MAVLink/include_v1.0/common/version.h b/libraries/GCS_MAVLink/include_v1.0/common/version.h
index 73c010209b..4941c1f885 100644
--- a/libraries/GCS_MAVLink/include_v1.0/common/version.h
+++ b/libraries/GCS_MAVLink/include_v1.0/common/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Sun Apr 1 16:31:09 2012"
+#define MAVLINK_BUILD_DATE "Mon Apr 2 09:57:26 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
index ced94d83e8..c2ed19bf25 100644
--- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
@@ -260,10 +260,10 @@
Status generated by radio
local signal strength
remote signal strength
+ how full the tx buffer is as a percentage
receive errors
serial errors
count of error corrected packets
- number of bytes available in transmit buffer
diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
index ced94d83e8..c2ed19bf25 100644
--- a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
@@ -260,10 +260,10 @@
Status generated by radio
local signal strength
remote signal strength
+ how full the tx buffer is as a percentage
receive errors
serial errors
count of error corrected packets
- number of bytes available in transmit buffer