source: flair-src/branches/mavlink/tools/Controller/Mavlink/src/include/common/mavlink_msg_rc_channels_override.h@ 75

Last change on this file since 75 was 75, checked in by Thomas Fuhrmann, 8 years ago

Change the version of mavlink generated messages and rename it to include

File size: 21.9 KB
Line 
1// MESSAGE RC_CHANNELS_OVERRIDE PACKING
2
3#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70
4
5typedef struct MAVLINK_PACKED __mavlink_rc_channels_override_t
6{
7 uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
8 uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
9 uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
10 uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
11 uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
12 uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
13 uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
14 uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/
15 uint8_t target_system; /*< System ID*/
16 uint8_t target_component; /*< Component ID*/
17} mavlink_rc_channels_override_t;
18
19#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18
20#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN 18
21#define MAVLINK_MSG_ID_70_LEN 18
22#define MAVLINK_MSG_ID_70_MIN_LEN 18
23
24#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124
25#define MAVLINK_MSG_ID_70_CRC 124
26
27
28
29#if MAVLINK_COMMAND_24BIT
30#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \
31 70, \
32 "RC_CHANNELS_OVERRIDE", \
33 10, \
34 { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \
35 { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \
36 { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \
37 { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \
38 { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \
39 { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \
40 { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \
41 { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \
42 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \
43 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \
44 } \
45}
46#else
47#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \
48 "RC_CHANNELS_OVERRIDE", \
49 10, \
50 { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \
51 { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \
52 { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \
53 { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \
54 { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \
55 { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \
56 { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \
57 { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \
58 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \
59 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \
60 } \
61}
62#endif
63
64/**
65 * @brief Pack a rc_channels_override message
66 * @param system_id ID of this system
67 * @param component_id ID of this component (e.g. 200 for IMU)
68 * @param msg The MAVLink message to compress the data into
69 *
70 * @param target_system System ID
71 * @param target_component Component ID
72 * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
73 * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
74 * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
75 * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
76 * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
77 * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
78 * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
79 * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
80 * @return length of the message in bytes (excluding serial stream start sign)
81 */
82static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
83 uint8_t target_system, uint8_t target_component, 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)
84{
85#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
86 char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN];
87 _mav_put_uint16_t(buf, 0, chan1_raw);
88 _mav_put_uint16_t(buf, 2, chan2_raw);
89 _mav_put_uint16_t(buf, 4, chan3_raw);
90 _mav_put_uint16_t(buf, 6, chan4_raw);
91 _mav_put_uint16_t(buf, 8, chan5_raw);
92 _mav_put_uint16_t(buf, 10, chan6_raw);
93 _mav_put_uint16_t(buf, 12, chan7_raw);
94 _mav_put_uint16_t(buf, 14, chan8_raw);
95 _mav_put_uint8_t(buf, 16, target_system);
96 _mav_put_uint8_t(buf, 17, target_component);
97
98 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
99#else
100 mavlink_rc_channels_override_t packet;
101 packet.chan1_raw = chan1_raw;
102 packet.chan2_raw = chan2_raw;
103 packet.chan3_raw = chan3_raw;
104 packet.chan4_raw = chan4_raw;
105 packet.chan5_raw = chan5_raw;
106 packet.chan6_raw = chan6_raw;
107 packet.chan7_raw = chan7_raw;
108 packet.chan8_raw = chan8_raw;
109 packet.target_system = target_system;
110 packet.target_component = target_component;
111
112 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
113#endif
114
115 msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
116 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
117}
118
119/**
120 * @brief Pack a rc_channels_override message on a channel
121 * @param system_id ID of this system
122 * @param component_id ID of this component (e.g. 200 for IMU)
123 * @param chan The MAVLink channel this message will be sent over
124 * @param msg The MAVLink message to compress the data into
125 * @param target_system System ID
126 * @param target_component Component ID
127 * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
128 * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
129 * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
130 * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
131 * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
132 * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
133 * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
134 * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
135 * @return length of the message in bytes (excluding serial stream start sign)
136 */
137static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
138 mavlink_message_t* msg,
139 uint8_t target_system,uint8_t target_component,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)
140{
141#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
142 char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN];
143 _mav_put_uint16_t(buf, 0, chan1_raw);
144 _mav_put_uint16_t(buf, 2, chan2_raw);
145 _mav_put_uint16_t(buf, 4, chan3_raw);
146 _mav_put_uint16_t(buf, 6, chan4_raw);
147 _mav_put_uint16_t(buf, 8, chan5_raw);
148 _mav_put_uint16_t(buf, 10, chan6_raw);
149 _mav_put_uint16_t(buf, 12, chan7_raw);
150 _mav_put_uint16_t(buf, 14, chan8_raw);
151 _mav_put_uint8_t(buf, 16, target_system);
152 _mav_put_uint8_t(buf, 17, target_component);
153
154 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
155#else
156 mavlink_rc_channels_override_t packet;
157 packet.chan1_raw = chan1_raw;
158 packet.chan2_raw = chan2_raw;
159 packet.chan3_raw = chan3_raw;
160 packet.chan4_raw = chan4_raw;
161 packet.chan5_raw = chan5_raw;
162 packet.chan6_raw = chan6_raw;
163 packet.chan7_raw = chan7_raw;
164 packet.chan8_raw = chan8_raw;
165 packet.target_system = target_system;
166 packet.target_component = target_component;
167
168 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
169#endif
170
171 msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
172 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
173}
174
175/**
176 * @brief Encode a rc_channels_override struct
177 *
178 * @param system_id ID of this system
179 * @param component_id ID of this component (e.g. 200 for IMU)
180 * @param msg The MAVLink message to compress the data into
181 * @param rc_channels_override C-struct to read the message contents from
182 */
183static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
184{
185 return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
186}
187
188/**
189 * @brief Encode a rc_channels_override struct on a channel
190 *
191 * @param system_id ID of this system
192 * @param component_id ID of this component (e.g. 200 for IMU)
193 * @param chan The MAVLink channel this message will be sent over
194 * @param msg The MAVLink message to compress the data into
195 * @param rc_channels_override C-struct to read the message contents from
196 */
197static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
198{
199 return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
200}
201
202/**
203 * @brief Send a rc_channels_override message
204 * @param chan MAVLink channel to send the message
205 *
206 * @param target_system System ID
207 * @param target_component Component ID
208 * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
209 * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
210 * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
211 * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
212 * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
213 * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
214 * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
215 * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
216 */
217#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
218
219static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, 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)
220{
221#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
222 char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN];
223 _mav_put_uint16_t(buf, 0, chan1_raw);
224 _mav_put_uint16_t(buf, 2, chan2_raw);
225 _mav_put_uint16_t(buf, 4, chan3_raw);
226 _mav_put_uint16_t(buf, 6, chan4_raw);
227 _mav_put_uint16_t(buf, 8, chan5_raw);
228 _mav_put_uint16_t(buf, 10, chan6_raw);
229 _mav_put_uint16_t(buf, 12, chan7_raw);
230 _mav_put_uint16_t(buf, 14, chan8_raw);
231 _mav_put_uint8_t(buf, 16, target_system);
232 _mav_put_uint8_t(buf, 17, target_component);
233
234 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
235#else
236 mavlink_rc_channels_override_t packet;
237 packet.chan1_raw = chan1_raw;
238 packet.chan2_raw = chan2_raw;
239 packet.chan3_raw = chan3_raw;
240 packet.chan4_raw = chan4_raw;
241 packet.chan5_raw = chan5_raw;
242 packet.chan6_raw = chan6_raw;
243 packet.chan7_raw = chan7_raw;
244 packet.chan8_raw = chan8_raw;
245 packet.target_system = target_system;
246 packet.target_component = target_component;
247
248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
249#endif
250}
251
252/**
253 * @brief Send a rc_channels_override message
254 * @param chan MAVLink channel to send the message
255 * @param struct The MAVLink struct to serialize
256 */
257static inline void mavlink_msg_rc_channels_override_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_override_t* rc_channels_override)
258{
259#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
260 mavlink_msg_rc_channels_override_send(chan, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
261#else
262 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)rc_channels_override, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
263#endif
264}
265
266#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
267/*
268 This varient of _send() can be used to save stack space by re-using
269 memory from the receive buffer. The caller provides a
270 mavlink_message_t which is the size of a full mavlink message. This
271 is usually the receive buffer for the channel, and allows a reply to an
272 incoming message with minimum stack space usage.
273 */
274static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, 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)
275{
276#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
277 char *buf = (char *)msgbuf;
278 _mav_put_uint16_t(buf, 0, chan1_raw);
279 _mav_put_uint16_t(buf, 2, chan2_raw);
280 _mav_put_uint16_t(buf, 4, chan3_raw);
281 _mav_put_uint16_t(buf, 6, chan4_raw);
282 _mav_put_uint16_t(buf, 8, chan5_raw);
283 _mav_put_uint16_t(buf, 10, chan6_raw);
284 _mav_put_uint16_t(buf, 12, chan7_raw);
285 _mav_put_uint16_t(buf, 14, chan8_raw);
286 _mav_put_uint8_t(buf, 16, target_system);
287 _mav_put_uint8_t(buf, 17, target_component);
288
289 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
290#else
291 mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf;
292 packet->chan1_raw = chan1_raw;
293 packet->chan2_raw = chan2_raw;
294 packet->chan3_raw = chan3_raw;
295 packet->chan4_raw = chan4_raw;
296 packet->chan5_raw = chan5_raw;
297 packet->chan6_raw = chan6_raw;
298 packet->chan7_raw = chan7_raw;
299 packet->chan8_raw = chan8_raw;
300 packet->target_system = target_system;
301 packet->target_component = target_component;
302
303 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
304#endif
305}
306#endif
307
308#endif
309
310// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING
311
312
313/**
314 * @brief Get field target_system from rc_channels_override message
315 *
316 * @return System ID
317 */
318static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg)
319{
320 return _MAV_RETURN_uint8_t(msg, 16);
321}
322
323/**
324 * @brief Get field target_component from rc_channels_override message
325 *
326 * @return Component ID
327 */
328static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg)
329{
330 return _MAV_RETURN_uint8_t(msg, 17);
331}
332
333/**
334 * @brief Get field chan1_raw from rc_channels_override message
335 *
336 * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
337 */
338static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg)
339{
340 return _MAV_RETURN_uint16_t(msg, 0);
341}
342
343/**
344 * @brief Get field chan2_raw from rc_channels_override message
345 *
346 * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
347 */
348static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg)
349{
350 return _MAV_RETURN_uint16_t(msg, 2);
351}
352
353/**
354 * @brief Get field chan3_raw from rc_channels_override message
355 *
356 * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
357 */
358static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg)
359{
360 return _MAV_RETURN_uint16_t(msg, 4);
361}
362
363/**
364 * @brief Get field chan4_raw from rc_channels_override message
365 *
366 * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
367 */
368static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg)
369{
370 return _MAV_RETURN_uint16_t(msg, 6);
371}
372
373/**
374 * @brief Get field chan5_raw from rc_channels_override message
375 *
376 * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
377 */
378static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg)
379{
380 return _MAV_RETURN_uint16_t(msg, 8);
381}
382
383/**
384 * @brief Get field chan6_raw from rc_channels_override message
385 *
386 * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
387 */
388static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg)
389{
390 return _MAV_RETURN_uint16_t(msg, 10);
391}
392
393/**
394 * @brief Get field chan7_raw from rc_channels_override message
395 *
396 * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
397 */
398static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg)
399{
400 return _MAV_RETURN_uint16_t(msg, 12);
401}
402
403/**
404 * @brief Get field chan8_raw from rc_channels_override message
405 *
406 * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
407 */
408static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg)
409{
410 return _MAV_RETURN_uint16_t(msg, 14);
411}
412
413/**
414 * @brief Decode a rc_channels_override message into a struct
415 *
416 * @param msg The message to decode
417 * @param rc_channels_override C-struct to decode the message contents into
418 */
419static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override)
420{
421#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
422 rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg);
423 rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg);
424 rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg);
425 rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg);
426 rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg);
427 rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg);
428 rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg);
429 rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg);
430 rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg);
431 rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg);
432#else
433 uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN;
434 memset(rc_channels_override, 0, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
435 memcpy(rc_channels_override, _MAV_PAYLOAD(msg), len);
436#endif
437}
Note: See TracBrowser for help on using the repository browser.