Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE RADIO PACKING
2
 
3
#define MAVLINK_MSG_ID_RADIO 166
4
 
5
typedef struct __mavlink_radio_t
6
{
7
 uint8_t rssi; ///< local signal strength
8
 uint8_t remrssi; ///< remote signal strength
9
 uint8_t txbuf; ///< how full the tx buffer is as a percentage
10
 uint8_t noise; ///< background noise level
11
 uint8_t remnoise; ///< remote background noise level
12
 uint16_t rxerrors; ///< receive errors
13
 uint16_t fixed; ///< count of error corrected packets
14
} mavlink_radio_t;
15
 
16
#define MAVLINK_MSG_ID_RADIO_LEN 9
17
#define MAVLINK_MSG_ID_166_LEN 9
18
 
19
 
20
 
21
#define MAVLINK_MESSAGE_INFO_RADIO { \
22
        "RADIO", \
23
        7, \
24
        {  { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_radio_t, rssi) }, \
25
         { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_radio_t, remrssi) }, \
26
         { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_radio_t, txbuf) }, \
27
         { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_radio_t, noise) }, \
28
         { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, remnoise) }, \
29
         { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, rxerrors) }, \
30
         { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \
31
         } \
32
}
33
 
34
 
35
/**
36
 * @brief Pack a radio message
37
 * @param system_id ID of this system
38
 * @param component_id ID of this component (e.g. 200 for IMU)
39
 * @param msg The MAVLink message to compress the data into
40
 *
41
 * @param rssi local signal strength
42
 * @param remrssi remote signal strength
43
 * @param txbuf how full the tx buffer is as a percentage
44
 * @param noise background noise level
45
 * @param remnoise remote background noise level
46
 * @param rxerrors receive errors
47
 * @param fixed count of error corrected packets
48
 * @return length of the message in bytes (excluding serial stream start sign)
49
 */
50
static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51
                                                       uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
52
{
53
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54
        char buf[9];
55
        _mav_put_uint8_t(buf, 0, rssi);
56
        _mav_put_uint8_t(buf, 1, remrssi);
57
        _mav_put_uint8_t(buf, 2, txbuf);
58
        _mav_put_uint8_t(buf, 3, noise);
59
        _mav_put_uint8_t(buf, 4, remnoise);
60
        _mav_put_uint16_t(buf, 5, rxerrors);
61
        _mav_put_uint16_t(buf, 7, fixed);
62
 
63
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
64
#else
65
        mavlink_radio_t packet;
66
        packet.rssi = rssi;
67
        packet.remrssi = remrssi;
68
        packet.txbuf = txbuf;
69
        packet.noise = noise;
70
        packet.remnoise = remnoise;
71
        packet.rxerrors = rxerrors;
72
        packet.fixed = fixed;
73
 
74
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
75
#endif
76
 
77
        msg->msgid = MAVLINK_MSG_ID_RADIO;
78
        return mavlink_finalize_message(msg, system_id, component_id, 9);
79
}
80
 
81
/**
82
 * @brief Pack a radio message on a channel
83
 * @param system_id ID of this system
84
 * @param component_id ID of this component (e.g. 200 for IMU)
85
 * @param chan The MAVLink channel this message was sent over
86
 * @param msg The MAVLink message to compress the data into
87
 * @param rssi local signal strength
88
 * @param remrssi remote signal strength
89
 * @param txbuf how full the tx buffer is as a percentage
90
 * @param noise background noise level
91
 * @param remnoise remote background noise level
92
 * @param rxerrors receive errors
93
 * @param fixed count of error corrected packets
94
 * @return length of the message in bytes (excluding serial stream start sign)
95
 */
96
static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97
                                                           mavlink_message_t* msg,
98
                                                           uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
99
{
100
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101
        char buf[9];
102
        _mav_put_uint8_t(buf, 0, rssi);
103
        _mav_put_uint8_t(buf, 1, remrssi);
104
        _mav_put_uint8_t(buf, 2, txbuf);
105
        _mav_put_uint8_t(buf, 3, noise);
106
        _mav_put_uint8_t(buf, 4, remnoise);
107
        _mav_put_uint16_t(buf, 5, rxerrors);
108
        _mav_put_uint16_t(buf, 7, fixed);
109
 
110
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
111
#else
112
        mavlink_radio_t packet;
113
        packet.rssi = rssi;
114
        packet.remrssi = remrssi;
115
        packet.txbuf = txbuf;
116
        packet.noise = noise;
117
        packet.remnoise = remnoise;
118
        packet.rxerrors = rxerrors;
119
        packet.fixed = fixed;
120
 
121
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
122
#endif
123
 
124
        msg->msgid = MAVLINK_MSG_ID_RADIO;
125
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9);
126
}
127
 
128
/**
129
 * @brief Encode a radio struct into a message
130
 *
131
 * @param system_id ID of this system
132
 * @param component_id ID of this component (e.g. 200 for IMU)
133
 * @param msg The MAVLink message to compress the data into
134
 * @param radio C-struct to read the message contents from
135
 */
136
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)
137
{
138
        return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
139
}
140
 
141
/**
142
 * @brief Send a radio message
143
 * @param chan MAVLink channel to send the message
144
 *
145
 * @param rssi local signal strength
146
 * @param remrssi remote signal strength
147
 * @param txbuf how full the tx buffer is as a percentage
148
 * @param noise background noise level
149
 * @param remnoise remote background noise level
150
 * @param rxerrors receive errors
151
 * @param fixed count of error corrected packets
152
 */
153
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
154
 
155
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)
156
{
157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
158
        char buf[9];
159
        _mav_put_uint8_t(buf, 0, rssi);
160
        _mav_put_uint8_t(buf, 1, remrssi);
161
        _mav_put_uint8_t(buf, 2, txbuf);
162
        _mav_put_uint8_t(buf, 3, noise);
163
        _mav_put_uint8_t(buf, 4, remnoise);
164
        _mav_put_uint16_t(buf, 5, rxerrors);
165
        _mav_put_uint16_t(buf, 7, fixed);
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9);
168
#else
169
        mavlink_radio_t packet;
170
        packet.rssi = rssi;
171
        packet.remrssi = remrssi;
172
        packet.txbuf = txbuf;
173
        packet.noise = noise;
174
        packet.remnoise = remnoise;
175
        packet.rxerrors = rxerrors;
176
        packet.fixed = fixed;
177
 
178
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9);
179
#endif
180
}
181
 
182
#endif
183
 
184
// MESSAGE RADIO UNPACKING
185
 
186
 
187
/**
188
 * @brief Get field rssi from radio message
189
 *
190
 * @return local signal strength
191
 */
192
static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
193
{
194
        return _MAV_RETURN_uint8_t(msg,  0);
195
}
196
 
197
/**
198
 * @brief Get field remrssi from radio message
199
 *
200
 * @return remote signal strength
201
 */
202
static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
203
{
204
        return _MAV_RETURN_uint8_t(msg,  1);
205
}
206
 
207
/**
208
 * @brief Get field txbuf from radio message
209
 *
210
 * @return how full the tx buffer is as a percentage
211
 */
212
static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
213
{
214
        return _MAV_RETURN_uint8_t(msg,  2);
215
}
216
 
217
/**
218
 * @brief Get field noise from radio message
219
 *
220
 * @return background noise level
221
 */
222
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
223
{
224
        return _MAV_RETURN_uint8_t(msg,  3);
225
}
226
 
227
/**
228
 * @brief Get field remnoise from radio message
229
 *
230
 * @return remote background noise level
231
 */
232
static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
233
{
234
        return _MAV_RETURN_uint8_t(msg,  4);
235
}
236
 
237
/**
238
 * @brief Get field rxerrors from radio message
239
 *
240
 * @return receive errors
241
 */
242
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
243
{
244
        return _MAV_RETURN_uint16_t(msg,  5);
245
}
246
 
247
/**
248
 * @brief Get field fixed from radio message
249
 *
250
 * @return count of error corrected packets
251
 */
252
static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
253
{
254
        return _MAV_RETURN_uint16_t(msg,  7);
255
}
256
 
257
/**
258
 * @brief Decode a radio message into a struct
259
 *
260
 * @param msg The message to decode
261
 * @param radio C-struct to decode the message contents into
262
 */
263
static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio)
264
{
265
#if MAVLINK_NEED_BYTE_SWAP
266
        radio->rssi = mavlink_msg_radio_get_rssi(msg);
267
        radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
268
        radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
269
        radio->noise = mavlink_msg_radio_get_noise(msg);
270
        radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
271
        radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
272
        radio->fixed = mavlink_msg_radio_get_fixed(msg);
273
#else
274
        memcpy(radio, _MAV_PAYLOAD(msg), 9);
275
#endif
276
}