MAVLink: imported new mavlink headers

this adds local and remote radio noise levels
This commit is contained in:
Andrew Tridgell 2012-04-08 11:30:32 +10:00
parent c7edd7857c
commit 7921d33c40
12 changed files with 149 additions and 99 deletions

View File

@ -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

View File

@ -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);
@ -203,22 +214,32 @@ static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field noise from radio message
*
* @return background noise level
*/
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_uint8_t(msg, 4);
}
/**
* @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, 3);
}
/**
* @brief Get field serrors from radio message
*
* @return serial errors
*/
static inline uint16_t mavlink_msg_radio_get_serrors(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);

View File

@ -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);
}

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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);
}
/**
@ -199,6 +210,26 @@ static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg
* @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, 6);
}
/**
* @brief Get field noise from radio message
*
* @return background noise level
*/
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @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_uint8_t(msg, 8);
}
@ -213,16 +244,6 @@ static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* m
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field serrors from radio message
*
* @return serial errors
*/
static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field fixed from radio message
*
@ -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

View File

@ -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);
}

View File

@ -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

View File

@ -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

View File

@ -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>

View File

@ -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>