Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE RC_CHANNELS_RAW PACKING
2
 
3
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
4
 
5
typedef struct __mavlink_rc_channels_raw_t
6
{
7
 uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
8
 uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
9
 uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
10
 uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
11
 uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
12
 uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
13
 uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
14
 uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
15
 uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
16
} mavlink_rc_channels_raw_t;
17
 
18
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 17
19
#define MAVLINK_MSG_ID_35_LEN 17
20
 
21
 
22
 
23
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \
24
        "RC_CHANNELS_RAW", \
25
        9, \
26
        {  { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \
27
         { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \
28
         { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \
29
         { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \
30
         { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \
31
         { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \
32
         { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \
33
         { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \
34
         { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, rssi) }, \
35
         } \
36
}
37
 
38
 
39
/**
40
 * @brief Pack a rc_channels_raw message
41
 * @param system_id ID of this system
42
 * @param component_id ID of this component (e.g. 200 for IMU)
43
 * @param msg The MAVLink message to compress the data into
44
 *
45
 * @param chan1_raw RC channel 1 value, in microseconds
46
 * @param chan2_raw RC channel 2 value, in microseconds
47
 * @param chan3_raw RC channel 3 value, in microseconds
48
 * @param chan4_raw RC channel 4 value, in microseconds
49
 * @param chan5_raw RC channel 5 value, in microseconds
50
 * @param chan6_raw RC channel 6 value, in microseconds
51
 * @param chan7_raw RC channel 7 value, in microseconds
52
 * @param chan8_raw RC channel 8 value, in microseconds
53
 * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
54
 * @return length of the message in bytes (excluding serial stream start sign)
55
 */
56
static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57
                                                       uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
58
{
59
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
60
        char buf[17];
61
        _mav_put_uint16_t(buf, 0, chan1_raw);
62
        _mav_put_uint16_t(buf, 2, chan2_raw);
63
        _mav_put_uint16_t(buf, 4, chan3_raw);
64
        _mav_put_uint16_t(buf, 6, chan4_raw);
65
        _mav_put_uint16_t(buf, 8, chan5_raw);
66
        _mav_put_uint16_t(buf, 10, chan6_raw);
67
        _mav_put_uint16_t(buf, 12, chan7_raw);
68
        _mav_put_uint16_t(buf, 14, chan8_raw);
69
        _mav_put_uint8_t(buf, 16, rssi);
70
 
71
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
72
#else
73
        mavlink_rc_channels_raw_t packet;
74
        packet.chan1_raw = chan1_raw;
75
        packet.chan2_raw = chan2_raw;
76
        packet.chan3_raw = chan3_raw;
77
        packet.chan4_raw = chan4_raw;
78
        packet.chan5_raw = chan5_raw;
79
        packet.chan6_raw = chan6_raw;
80
        packet.chan7_raw = chan7_raw;
81
        packet.chan8_raw = chan8_raw;
82
        packet.rssi = rssi;
83
 
84
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
85
#endif
86
 
87
        msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
88
        return mavlink_finalize_message(msg, system_id, component_id, 17);
89
}
90
 
91
/**
92
 * @brief Pack a rc_channels_raw message on a channel
93
 * @param system_id ID of this system
94
 * @param component_id ID of this component (e.g. 200 for IMU)
95
 * @param chan The MAVLink channel this message was sent over
96
 * @param msg The MAVLink message to compress the data into
97
 * @param chan1_raw RC channel 1 value, in microseconds
98
 * @param chan2_raw RC channel 2 value, in microseconds
99
 * @param chan3_raw RC channel 3 value, in microseconds
100
 * @param chan4_raw RC channel 4 value, in microseconds
101
 * @param chan5_raw RC channel 5 value, in microseconds
102
 * @param chan6_raw RC channel 6 value, in microseconds
103
 * @param chan7_raw RC channel 7 value, in microseconds
104
 * @param chan8_raw RC channel 8 value, in microseconds
105
 * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
106
 * @return length of the message in bytes (excluding serial stream start sign)
107
 */
108
static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
109
                                                           mavlink_message_t* msg,
110
                                                           uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi)
111
{
112
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
113
        char buf[17];
114
        _mav_put_uint16_t(buf, 0, chan1_raw);
115
        _mav_put_uint16_t(buf, 2, chan2_raw);
116
        _mav_put_uint16_t(buf, 4, chan3_raw);
117
        _mav_put_uint16_t(buf, 6, chan4_raw);
118
        _mav_put_uint16_t(buf, 8, chan5_raw);
119
        _mav_put_uint16_t(buf, 10, chan6_raw);
120
        _mav_put_uint16_t(buf, 12, chan7_raw);
121
        _mav_put_uint16_t(buf, 14, chan8_raw);
122
        _mav_put_uint8_t(buf, 16, rssi);
123
 
124
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
125
#else
126
        mavlink_rc_channels_raw_t packet;
127
        packet.chan1_raw = chan1_raw;
128
        packet.chan2_raw = chan2_raw;
129
        packet.chan3_raw = chan3_raw;
130
        packet.chan4_raw = chan4_raw;
131
        packet.chan5_raw = chan5_raw;
132
        packet.chan6_raw = chan6_raw;
133
        packet.chan7_raw = chan7_raw;
134
        packet.chan8_raw = chan8_raw;
135
        packet.rssi = rssi;
136
 
137
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
138
#endif
139
 
140
        msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
141
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17);
142
}
143
 
144
/**
145
 * @brief Encode a rc_channels_raw struct into a message
146
 *
147
 * @param system_id ID of this system
148
 * @param component_id ID of this component (e.g. 200 for IMU)
149
 * @param msg The MAVLink message to compress the data into
150
 * @param rc_channels_raw C-struct to read the message contents from
151
 */
152
static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
153
{
154
        return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
155
}
156
 
157
/**
158
 * @brief Send a rc_channels_raw message
159
 * @param chan MAVLink channel to send the message
160
 *
161
 * @param chan1_raw RC channel 1 value, in microseconds
162
 * @param chan2_raw RC channel 2 value, in microseconds
163
 * @param chan3_raw RC channel 3 value, in microseconds
164
 * @param chan4_raw RC channel 4 value, in microseconds
165
 * @param chan5_raw RC channel 5 value, in microseconds
166
 * @param chan6_raw RC channel 6 value, in microseconds
167
 * @param chan7_raw RC channel 7 value, in microseconds
168
 * @param chan8_raw RC channel 8 value, in microseconds
169
 * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
170
 */
171
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
172
 
173
static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
174
{
175
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
176
        char buf[17];
177
        _mav_put_uint16_t(buf, 0, chan1_raw);
178
        _mav_put_uint16_t(buf, 2, chan2_raw);
179
        _mav_put_uint16_t(buf, 4, chan3_raw);
180
        _mav_put_uint16_t(buf, 6, chan4_raw);
181
        _mav_put_uint16_t(buf, 8, chan5_raw);
182
        _mav_put_uint16_t(buf, 10, chan6_raw);
183
        _mav_put_uint16_t(buf, 12, chan7_raw);
184
        _mav_put_uint16_t(buf, 14, chan8_raw);
185
        _mav_put_uint8_t(buf, 16, rssi);
186
 
187
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, 17);
188
#else
189
        mavlink_rc_channels_raw_t packet;
190
        packet.chan1_raw = chan1_raw;
191
        packet.chan2_raw = chan2_raw;
192
        packet.chan3_raw = chan3_raw;
193
        packet.chan4_raw = chan4_raw;
194
        packet.chan5_raw = chan5_raw;
195
        packet.chan6_raw = chan6_raw;
196
        packet.chan7_raw = chan7_raw;
197
        packet.chan8_raw = chan8_raw;
198
        packet.rssi = rssi;
199
 
200
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, 17);
201
#endif
202
}
203
 
204
#endif
205
 
206
// MESSAGE RC_CHANNELS_RAW UNPACKING
207
 
208
 
209
/**
210
 * @brief Get field chan1_raw from rc_channels_raw message
211
 *
212
 * @return RC channel 1 value, in microseconds
213
 */
214
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
215
{
216
        return _MAV_RETURN_uint16_t(msg,  0);
217
}
218
 
219
/**
220
 * @brief Get field chan2_raw from rc_channels_raw message
221
 *
222
 * @return RC channel 2 value, in microseconds
223
 */
224
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
225
{
226
        return _MAV_RETURN_uint16_t(msg,  2);
227
}
228
 
229
/**
230
 * @brief Get field chan3_raw from rc_channels_raw message
231
 *
232
 * @return RC channel 3 value, in microseconds
233
 */
234
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
235
{
236
        return _MAV_RETURN_uint16_t(msg,  4);
237
}
238
 
239
/**
240
 * @brief Get field chan4_raw from rc_channels_raw message
241
 *
242
 * @return RC channel 4 value, in microseconds
243
 */
244
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
245
{
246
        return _MAV_RETURN_uint16_t(msg,  6);
247
}
248
 
249
/**
250
 * @brief Get field chan5_raw from rc_channels_raw message
251
 *
252
 * @return RC channel 5 value, in microseconds
253
 */
254
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
255
{
256
        return _MAV_RETURN_uint16_t(msg,  8);
257
}
258
 
259
/**
260
 * @brief Get field chan6_raw from rc_channels_raw message
261
 *
262
 * @return RC channel 6 value, in microseconds
263
 */
264
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
265
{
266
        return _MAV_RETURN_uint16_t(msg,  10);
267
}
268
 
269
/**
270
 * @brief Get field chan7_raw from rc_channels_raw message
271
 *
272
 * @return RC channel 7 value, in microseconds
273
 */
274
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
275
{
276
        return _MAV_RETURN_uint16_t(msg,  12);
277
}
278
 
279
/**
280
 * @brief Get field chan8_raw from rc_channels_raw message
281
 *
282
 * @return RC channel 8 value, in microseconds
283
 */
284
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
285
{
286
        return _MAV_RETURN_uint16_t(msg,  14);
287
}
288
 
289
/**
290
 * @brief Get field rssi from rc_channels_raw message
291
 *
292
 * @return Receive signal strength indicator, 0: 0%, 255: 100%
293
 */
294
static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg)
295
{
296
        return _MAV_RETURN_uint8_t(msg,  16);
297
}
298
 
299
/**
300
 * @brief Decode a rc_channels_raw message into a struct
301
 *
302
 * @param msg The message to decode
303
 * @param rc_channels_raw C-struct to decode the message contents into
304
 */
305
static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
306
{
307
#if MAVLINK_NEED_BYTE_SWAP
308
        rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);
309
        rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg);
310
        rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg);
311
        rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg);
312
        rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg);
313
        rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg);
314
        rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg);
315
        rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg);
316
        rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg);
317
#else
318
        memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), 17);
319
#endif
320
}