4#define MAVLINK_MSG_ID_RC_CHANNELS 65
7typedef struct __mavlink_rc_channels_t {
29}) mavlink_rc_channels_t;
31#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42
32#define MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN 42
33#define MAVLINK_MSG_ID_65_LEN 42
34#define MAVLINK_MSG_ID_65_MIN_LEN 42
36#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118
37#define MAVLINK_MSG_ID_65_CRC 118
41#if MAVLINK_COMMAND_24BIT
42#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \
46 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
47 { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
48 { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
49 { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
50 { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
51 { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
52 { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
53 { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
54 { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
55 { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
56 { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
57 { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
58 { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
59 { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
60 { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
61 { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
62 { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
63 { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
64 { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
65 { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
66 { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
70#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \
73 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
74 { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
75 { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
76 { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
77 { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
78 { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
79 { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
80 { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
81 { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
82 { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
83 { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
84 { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
85 { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
86 { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
87 { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
88 { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
89 { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
90 { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
91 { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
92 { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
93 { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
127static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
128 uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
130#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
131 char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
132 _mav_put_uint32_t(buf, 0, time_boot_ms);
133 _mav_put_uint16_t(buf, 4, chan1_raw);
134 _mav_put_uint16_t(buf, 6, chan2_raw);
135 _mav_put_uint16_t(buf, 8, chan3_raw);
136 _mav_put_uint16_t(buf, 10, chan4_raw);
137 _mav_put_uint16_t(buf, 12, chan5_raw);
138 _mav_put_uint16_t(buf, 14, chan6_raw);
139 _mav_put_uint16_t(buf, 16, chan7_raw);
140 _mav_put_uint16_t(buf, 18, chan8_raw);
141 _mav_put_uint16_t(buf, 20, chan9_raw);
142 _mav_put_uint16_t(buf, 22, chan10_raw);
143 _mav_put_uint16_t(buf, 24, chan11_raw);
144 _mav_put_uint16_t(buf, 26, chan12_raw);
145 _mav_put_uint16_t(buf, 28, chan13_raw);
146 _mav_put_uint16_t(buf, 30, chan14_raw);
147 _mav_put_uint16_t(buf, 32, chan15_raw);
148 _mav_put_uint16_t(buf, 34, chan16_raw);
149 _mav_put_uint16_t(buf, 36, chan17_raw);
150 _mav_put_uint16_t(buf, 38, chan18_raw);
151 _mav_put_uint8_t(buf, 40, chancount);
152 _mav_put_uint8_t(buf, 41, rssi);
154 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
156 mavlink_rc_channels_t packet;
157 packet.time_boot_ms = time_boot_ms;
158 packet.chan1_raw = chan1_raw;
159 packet.chan2_raw = chan2_raw;
160 packet.chan3_raw = chan3_raw;
161 packet.chan4_raw = chan4_raw;
162 packet.chan5_raw = chan5_raw;
163 packet.chan6_raw = chan6_raw;
164 packet.chan7_raw = chan7_raw;
165 packet.chan8_raw = chan8_raw;
166 packet.chan9_raw = chan9_raw;
167 packet.chan10_raw = chan10_raw;
168 packet.chan11_raw = chan11_raw;
169 packet.chan12_raw = chan12_raw;
170 packet.chan13_raw = chan13_raw;
171 packet.chan14_raw = chan14_raw;
172 packet.chan15_raw = chan15_raw;
173 packet.chan16_raw = chan16_raw;
174 packet.chan17_raw = chan17_raw;
175 packet.chan18_raw = chan18_raw;
176 packet.chancount = chancount;
179 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
182 msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
183 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
215static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
216 mavlink_message_t* msg,
217 uint32_t time_boot_ms,uint8_t chancount,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,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi)
219#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220 char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
221 _mav_put_uint32_t(buf, 0, time_boot_ms);
222 _mav_put_uint16_t(buf, 4, chan1_raw);
223 _mav_put_uint16_t(buf, 6, chan2_raw);
224 _mav_put_uint16_t(buf, 8, chan3_raw);
225 _mav_put_uint16_t(buf, 10, chan4_raw);
226 _mav_put_uint16_t(buf, 12, chan5_raw);
227 _mav_put_uint16_t(buf, 14, chan6_raw);
228 _mav_put_uint16_t(buf, 16, chan7_raw);
229 _mav_put_uint16_t(buf, 18, chan8_raw);
230 _mav_put_uint16_t(buf, 20, chan9_raw);
231 _mav_put_uint16_t(buf, 22, chan10_raw);
232 _mav_put_uint16_t(buf, 24, chan11_raw);
233 _mav_put_uint16_t(buf, 26, chan12_raw);
234 _mav_put_uint16_t(buf, 28, chan13_raw);
235 _mav_put_uint16_t(buf, 30, chan14_raw);
236 _mav_put_uint16_t(buf, 32, chan15_raw);
237 _mav_put_uint16_t(buf, 34, chan16_raw);
238 _mav_put_uint16_t(buf, 36, chan17_raw);
239 _mav_put_uint16_t(buf, 38, chan18_raw);
240 _mav_put_uint8_t(buf, 40, chancount);
241 _mav_put_uint8_t(buf, 41, rssi);
243 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
245 mavlink_rc_channels_t packet;
246 packet.time_boot_ms = time_boot_ms;
247 packet.chan1_raw = chan1_raw;
248 packet.chan2_raw = chan2_raw;
249 packet.chan3_raw = chan3_raw;
250 packet.chan4_raw = chan4_raw;
251 packet.chan5_raw = chan5_raw;
252 packet.chan6_raw = chan6_raw;
253 packet.chan7_raw = chan7_raw;
254 packet.chan8_raw = chan8_raw;
255 packet.chan9_raw = chan9_raw;
256 packet.chan10_raw = chan10_raw;
257 packet.chan11_raw = chan11_raw;
258 packet.chan12_raw = chan12_raw;
259 packet.chan13_raw = chan13_raw;
260 packet.chan14_raw = chan14_raw;
261 packet.chan15_raw = chan15_raw;
262 packet.chan16_raw = chan16_raw;
263 packet.chan17_raw = chan17_raw;
264 packet.chan18_raw = chan18_raw;
265 packet.chancount = chancount;
268 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
271 msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
272 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
283static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_rc_channels_t* rc_channels)
285 return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
297static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_rc_channels_t* rc_channels)
299 return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
328#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
330static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
332#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
333 char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
334 _mav_put_uint32_t(buf, 0, time_boot_ms);
335 _mav_put_uint16_t(buf, 4, chan1_raw);
336 _mav_put_uint16_t(buf, 6, chan2_raw);
337 _mav_put_uint16_t(buf, 8, chan3_raw);
338 _mav_put_uint16_t(buf, 10, chan4_raw);
339 _mav_put_uint16_t(buf, 12, chan5_raw);
340 _mav_put_uint16_t(buf, 14, chan6_raw);
341 _mav_put_uint16_t(buf, 16, chan7_raw);
342 _mav_put_uint16_t(buf, 18, chan8_raw);
343 _mav_put_uint16_t(buf, 20, chan9_raw);
344 _mav_put_uint16_t(buf, 22, chan10_raw);
345 _mav_put_uint16_t(buf, 24, chan11_raw);
346 _mav_put_uint16_t(buf, 26, chan12_raw);
347 _mav_put_uint16_t(buf, 28, chan13_raw);
348 _mav_put_uint16_t(buf, 30, chan14_raw);
349 _mav_put_uint16_t(buf, 32, chan15_raw);
350 _mav_put_uint16_t(buf, 34, chan16_raw);
351 _mav_put_uint16_t(buf, 36, chan17_raw);
352 _mav_put_uint16_t(buf, 38, chan18_raw);
353 _mav_put_uint8_t(buf, 40, chancount);
354 _mav_put_uint8_t(buf, 41, rssi);
356 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
358 mavlink_rc_channels_t packet;
359 packet.time_boot_ms = time_boot_ms;
360 packet.chan1_raw = chan1_raw;
361 packet.chan2_raw = chan2_raw;
362 packet.chan3_raw = chan3_raw;
363 packet.chan4_raw = chan4_raw;
364 packet.chan5_raw = chan5_raw;
365 packet.chan6_raw = chan6_raw;
366 packet.chan7_raw = chan7_raw;
367 packet.chan8_raw = chan8_raw;
368 packet.chan9_raw = chan9_raw;
369 packet.chan10_raw = chan10_raw;
370 packet.chan11_raw = chan11_raw;
371 packet.chan12_raw = chan12_raw;
372 packet.chan13_raw = chan13_raw;
373 packet.chan14_raw = chan14_raw;
374 packet.chan15_raw = chan15_raw;
375 packet.chan16_raw = chan16_raw;
376 packet.chan17_raw = chan17_raw;
377 packet.chan18_raw = chan18_raw;
378 packet.chancount = chancount;
381 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (
const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
390static inline void mavlink_msg_rc_channels_send_struct(mavlink_channel_t chan,
const mavlink_rc_channels_t* rc_channels)
392#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
393 mavlink_msg_rc_channels_send(chan, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
395 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (
const char *)rc_channels, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
399#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
407static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
409#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
410 char *buf = (
char *)msgbuf;
411 _mav_put_uint32_t(buf, 0, time_boot_ms);
412 _mav_put_uint16_t(buf, 4, chan1_raw);
413 _mav_put_uint16_t(buf, 6, chan2_raw);
414 _mav_put_uint16_t(buf, 8, chan3_raw);
415 _mav_put_uint16_t(buf, 10, chan4_raw);
416 _mav_put_uint16_t(buf, 12, chan5_raw);
417 _mav_put_uint16_t(buf, 14, chan6_raw);
418 _mav_put_uint16_t(buf, 16, chan7_raw);
419 _mav_put_uint16_t(buf, 18, chan8_raw);
420 _mav_put_uint16_t(buf, 20, chan9_raw);
421 _mav_put_uint16_t(buf, 22, chan10_raw);
422 _mav_put_uint16_t(buf, 24, chan11_raw);
423 _mav_put_uint16_t(buf, 26, chan12_raw);
424 _mav_put_uint16_t(buf, 28, chan13_raw);
425 _mav_put_uint16_t(buf, 30, chan14_raw);
426 _mav_put_uint16_t(buf, 32, chan15_raw);
427 _mav_put_uint16_t(buf, 34, chan16_raw);
428 _mav_put_uint16_t(buf, 36, chan17_raw);
429 _mav_put_uint16_t(buf, 38, chan18_raw);
430 _mav_put_uint8_t(buf, 40, chancount);
431 _mav_put_uint8_t(buf, 41, rssi);
433 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
435 mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf;
436 packet->time_boot_ms = time_boot_ms;
437 packet->chan1_raw = chan1_raw;
438 packet->chan2_raw = chan2_raw;
439 packet->chan3_raw = chan3_raw;
440 packet->chan4_raw = chan4_raw;
441 packet->chan5_raw = chan5_raw;
442 packet->chan6_raw = chan6_raw;
443 packet->chan7_raw = chan7_raw;
444 packet->chan8_raw = chan8_raw;
445 packet->chan9_raw = chan9_raw;
446 packet->chan10_raw = chan10_raw;
447 packet->chan11_raw = chan11_raw;
448 packet->chan12_raw = chan12_raw;
449 packet->chan13_raw = chan13_raw;
450 packet->chan14_raw = chan14_raw;
451 packet->chan15_raw = chan15_raw;
452 packet->chan16_raw = chan16_raw;
453 packet->chan17_raw = chan17_raw;
454 packet->chan18_raw = chan18_raw;
455 packet->chancount = chancount;
458 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (
const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
473static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(
const mavlink_message_t* msg)
475 return _MAV_RETURN_uint32_t(msg, 0);
483static inline uint8_t mavlink_msg_rc_channels_get_chancount(
const mavlink_message_t* msg)
485 return _MAV_RETURN_uint8_t(msg, 40);
493static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(
const mavlink_message_t* msg)
495 return _MAV_RETURN_uint16_t(msg, 4);
503static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(
const mavlink_message_t* msg)
505 return _MAV_RETURN_uint16_t(msg, 6);
513static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(
const mavlink_message_t* msg)
515 return _MAV_RETURN_uint16_t(msg, 8);
523static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(
const mavlink_message_t* msg)
525 return _MAV_RETURN_uint16_t(msg, 10);
533static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(
const mavlink_message_t* msg)
535 return _MAV_RETURN_uint16_t(msg, 12);
543static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(
const mavlink_message_t* msg)
545 return _MAV_RETURN_uint16_t(msg, 14);
553static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(
const mavlink_message_t* msg)
555 return _MAV_RETURN_uint16_t(msg, 16);
563static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(
const mavlink_message_t* msg)
565 return _MAV_RETURN_uint16_t(msg, 18);
573static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(
const mavlink_message_t* msg)
575 return _MAV_RETURN_uint16_t(msg, 20);
583static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(
const mavlink_message_t* msg)
585 return _MAV_RETURN_uint16_t(msg, 22);
593static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(
const mavlink_message_t* msg)
595 return _MAV_RETURN_uint16_t(msg, 24);
603static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(
const mavlink_message_t* msg)
605 return _MAV_RETURN_uint16_t(msg, 26);
613static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(
const mavlink_message_t* msg)
615 return _MAV_RETURN_uint16_t(msg, 28);
623static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(
const mavlink_message_t* msg)
625 return _MAV_RETURN_uint16_t(msg, 30);
633static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(
const mavlink_message_t* msg)
635 return _MAV_RETURN_uint16_t(msg, 32);
643static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(
const mavlink_message_t* msg)
645 return _MAV_RETURN_uint16_t(msg, 34);
653static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(
const mavlink_message_t* msg)
655 return _MAV_RETURN_uint16_t(msg, 36);
663static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(
const mavlink_message_t* msg)
665 return _MAV_RETURN_uint16_t(msg, 38);
673static inline uint8_t mavlink_msg_rc_channels_get_rssi(
const mavlink_message_t* msg)
675 return _MAV_RETURN_uint8_t(msg, 41);
684static inline void mavlink_msg_rc_channels_decode(
const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels)
686#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
687 rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg);
688 rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg);
689 rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg);
690 rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg);
691 rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg);
692 rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg);
693 rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg);
694 rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg);
695 rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg);
696 rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg);
697 rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg);
698 rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg);
699 rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg);
700 rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg);
701 rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg);
702 rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg);
703 rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg);
704 rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg);
705 rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg);
706 rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg);
707 rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg);
709 uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_LEN;
710 memset(rc_channels, 0, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
711 memcpy(rc_channels, _MAV_PAYLOAD(msg), len);