diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
index 72ebba618dd0cc2df0d4ea6f00a31512801630f8..204c907555b2bcfc3469d6107346f483f4865c60 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
@@ -16,7 +16,7 @@ extern "C" {
 #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, 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}
+#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, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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 1a403982011a3bbd3445b83634751b14ed2fa637..ee7e8f16cff35cb9eb759bec7c990bd648442eaf 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
@@ -7,8 +7,9 @@ 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
+ uint8_t noise; ///< background noise level
+ uint8_t remnoise; ///< remote background noise level
  uint16_t rxerrors; ///< receive errors
- uint16_t serrors; ///< serial errors
  uint16_t fixed; ///< count of error corrected packets
 } mavlink_radio_t;
 
@@ -19,12 +20,13 @@ typedef struct __mavlink_radio_t
 
 #define MAVLINK_MESSAGE_INFO_RADIO { \
 	"RADIO", \
-	6, \
+	7, \
 	{  { "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) }, \
          { "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) }, \
+         { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_radio_t, noise) }, \
+         { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, remnoise) }, \
+         { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, rxerrors) }, \
          { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \
          } \
 }
@@ -39,21 +41,23 @@ 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_uint8_t(buf, 0, rssi);
 	_mav_put_uint8_t(buf, 1, remrssi);
 	_mav_put_uint8_t(buf, 2, txbuf);
-	_mav_put_uint16_t(buf, 3, rxerrors);
-	_mav_put_uint16_t(buf, 5, serrors);
+	_mav_put_uint8_t(buf, 3, noise);
+	_mav_put_uint8_t(buf, 4, remnoise);
+	_mav_put_uint16_t(buf, 5, rxerrors);
 	_mav_put_uint16_t(buf, 7, fixed);
 
         memcpy(_MAV_PAYLOAD(msg), buf, 9);
@@ -62,8 +66,9 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 
         memcpy(_MAV_PAYLOAD(msg), &packet, 9);
@@ -82,22 +87,24 @@ 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_uint8_t(buf, 0, rssi);
 	_mav_put_uint8_t(buf, 1, remrssi);
 	_mav_put_uint8_t(buf, 2, txbuf);
-	_mav_put_uint16_t(buf, 3, rxerrors);
-	_mav_put_uint16_t(buf, 5, serrors);
+	_mav_put_uint8_t(buf, 3, noise);
+	_mav_put_uint8_t(buf, 4, remnoise);
+	_mav_put_uint16_t(buf, 5, rxerrors);
 	_mav_put_uint16_t(buf, 7, fixed);
 
         memcpy(_MAV_PAYLOAD(msg), buf, 9);
@@ -106,8 +113,9 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 
         memcpy(_MAV_PAYLOAD(msg), &packet, 9);
@@ -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,21 +145,23 @@ 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_uint8_t(buf, 0, rssi);
 	_mav_put_uint8_t(buf, 1, remrssi);
 	_mav_put_uint8_t(buf, 2, txbuf);
-	_mav_put_uint16_t(buf, 3, rxerrors);
-	_mav_put_uint16_t(buf, 5, serrors);
+	_mav_put_uint8_t(buf, 3, noise);
+	_mav_put_uint8_t(buf, 4, remnoise);
+	_mav_put_uint16_t(buf, 5, rxerrors);
 	_mav_put_uint16_t(buf, 7, fixed);
 
 	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9);
@@ -160,8 +170,9 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi,
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 
 	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9);
@@ -204,21 +215,31 @@ static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
 }
 
 /**
- * @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_uint8_t(msg,  3);
+}
+
+/**
+ * @brief Get field remnoise from radio message
+ *
+ * @return remote background noise level
+ */
+static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint16_t(msg,  3);
+	return _MAV_RETURN_uint8_t(msg,  4);
 }
 
 /**
- * @brief Get field serrors from radio message
+ * @brief Get field rxerrors from radio message
  *
- * @return serial errors
+ * @return receive errors
  */
-static inline uint16_t mavlink_msg_radio_get_serrors(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,  5);
 }
@@ -245,8 +266,9 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
 	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);
 	radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
-	radio->serrors = mavlink_msg_radio_get_serrors(msg);
 	radio->fixed = mavlink_msg_radio_get_fixed(msg);
 #else
 	memcpy(radio, _MAV_PAYLOAD(msg), 9);
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
index d35e81bd4bd63270f95618465f1f746f808afe7c..cbc002d64f401b93ac90560e226fd86e5debe1ed 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
@@ -836,7 +836,8 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 		5,
 	72,
 	139,
-	17391,
+	206,
+	17,
 	17495,
 	17599,
 	};
@@ -845,8 +846,9 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 		packet1.rssi = packet_in.rssi;
 		packet1.remrssi = packet_in.remrssi;
 		packet1.txbuf = packet_in.txbuf;
+		packet1.noise = packet_in.noise;
+		packet1.remnoise = packet_in.remnoise;
 		packet1.rxerrors = packet_in.rxerrors;
-		packet1.serrors = packet_in.serrors;
 		packet1.fixed = packet_in.fixed;
 
 
@@ -857,12 +859,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.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , 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.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -875,7 +877,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.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , 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 78e9d02f517adc0888e10a76d90b3ff75d32931f..92c94399fe27f24a364b13920f3aa95441dad220 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 "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:51 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 edc521ae72d92c60ddc775582d10e9b2a7ae9832..4eab9a8979482ebcdf2b564ce6935e3c83570ca5 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 "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:51 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 0d168ba758b5f57f4fe6ed59e64c5b1c7f70188a..4325b57e21bcc0af9183326df894c4698dfc4899 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
@@ -16,7 +16,7 @@ extern "C" {
 #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, 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}
+#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, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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 546daddd1d4cd105855ae550317503327e7fa07c..db64da5c31d81512e2040b86a3db4c8d43654df6 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
@@ -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
 
 #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
  * @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
  * @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
  */
 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
  * @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,
  */
 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)
  */
 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
  */
 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
  */
 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
 {
 #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
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
index 12f9aad722b6b1d1e201a8e0e8582cf14b4adf16..acd50ec021101c092b8ef06cee078273463cd262 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
@@ -835,7 +835,8 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 	mavlink_radio_t packet_in = {
 		17235,
 	17339,
-	17443,
+	17,
+	84,
 	151,
 	218,
 	29,
@@ -843,11 +844,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 	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.rssi = packet_in.rssi;
 		packet1.remrssi = packet_in.remrssi;
 		packet1.txbuf = packet_in.txbuf;
+		packet1.noise = packet_in.noise;
+		packet1.remnoise = packet_in.remnoise;
 
 
 
@@ -857,12 +859,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.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , 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.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -875,7 +877,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.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , 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 979dcb63672740859fb65647b089f6537ace68ba..1544c0de52879c963ddd1671ba221d307403bb4c 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 "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:52 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 4941c1f8853d9fa160f67bc6274ed03841af07e8..f683e8c872932200937552542d9726e584da159d 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 "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:52 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 c2ed19bf251d6cf4b682d97e6e0f9b883a3dd07f..c6019e03f24a8dae74646f103d19675740b7424c 100644
--- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
@@ -261,8 +261,9 @@
             <field type="uint8_t" name="rssi">local signal strength</field>
             <field type="uint8_t" name="remrssi">remote signal strength</field>
 	    <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
+            <field type="uint8_t" name="noise">background noise level</field>
+            <field type="uint8_t" name="remnoise">remote background noise level</field>
 	    <field type="uint16_t" name="rxerrors">receive errors</field>
-	    <field type="uint16_t" name="serrors">serial errors</field>
 	    <field type="uint16_t" name="fixed">count of error corrected packets</field>
 	  </message>
      </messages>
diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
index c2ed19bf251d6cf4b682d97e6e0f9b883a3dd07f..c6019e03f24a8dae74646f103d19675740b7424c 100644
--- a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
@@ -261,8 +261,9 @@
             <field type="uint8_t" name="rssi">local signal strength</field>
             <field type="uint8_t" name="remrssi">remote signal strength</field>
 	    <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
+            <field type="uint8_t" name="noise">background noise level</field>
+            <field type="uint8_t" name="remnoise">remote background noise level</field>
 	    <field type="uint16_t" name="rxerrors">receive errors</field>
-	    <field type="uint16_t" name="serrors">serial errors</field>
 	    <field type="uint16_t" name="fixed">count of error corrected packets</field>
 	  </message>
      </messages>